Skip to content

Commit

Permalink
Tune parameters
Browse files Browse the repository at this point in the history
  • Loading branch information
amalnanavati committed Dec 16, 2024
1 parent 950a83b commit a2cd3e0
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
9 changes: 4 additions & 5 deletions ada_moveit/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@ planner_configs:
type: geometric::AnytimePathShortening
shortcut: 1 # Attempt to shortcut all new solution paths
hybridize: 1 # Compute hybrid solution trajectories
max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
max_hybrid_paths: 8 # Number of hybrid paths generated per iteration
num_planners: 4 # The number of default planners to use for planning
planners: "RRTConnect" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
planners: "RRTConnect[intermediate_states=0 range=0.05]" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
SBLkConfigDefault:
type: geometric::SBL
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
Expand Down Expand Up @@ -49,7 +49,8 @@ planner_configs:
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
RRTConnectkConfigDefault:
type: geometric::RRTConnect
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
intermediate_states: 0 # Whether to add intermediate states to the plan, default 0
range: 0.05 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
RRTstarkConfigDefault:
type: geometric::RRTstar
range: 3.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() (in practice, for ADA, this default is ~7)
Expand Down Expand Up @@ -88,8 +89,6 @@ jaco_arm:
- PRMkConfigDefault
- PRMstarkConfigDefault
hand:
enforce_constrained_state_space: true
projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2)
planner_configs:
- SBLkConfigDefault
- ESTkConfigDefault
Expand Down
4 changes: 3 additions & 1 deletion ada_moveit/launch/demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -261,7 +261,9 @@ def generate_launch_description():
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
arguments=["--ros-args", "--log-level", log_level],
# Commented out the log-level since the joint state publisher logs every joint read
# when on debug level
arguments=["--ros-args"],#, "--log-level", log_level],
)
)

Expand Down

0 comments on commit a2cd3e0

Please sign in to comment.