Skip to content

Commit a2cd3e0

Browse files
committed
Tune parameters
1 parent 950a83b commit a2cd3e0

File tree

2 files changed

+7
-6
lines changed

2 files changed

+7
-6
lines changed

ada_moveit/config/ompl_planning.yaml

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@ planner_configs:
1515
type: geometric::AnytimePathShortening
1616
shortcut: 1 # Attempt to shortcut all new solution paths
1717
hybridize: 1 # Compute hybrid solution trajectories
18-
max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
18+
max_hybrid_paths: 8 # Number of hybrid paths generated per iteration
1919
num_planners: 4 # The number of default planners to use for planning
20-
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]"
20+
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]"
2121
SBLkConfigDefault:
2222
type: geometric::SBL
2323
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
@@ -49,7 +49,8 @@ planner_configs:
4949
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
5050
RRTConnectkConfigDefault:
5151
type: geometric::RRTConnect
52-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
52+
intermediate_states: 0 # Whether to add intermediate states to the plan, default 0
53+
range: 0.05 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
5354
RRTstarkConfigDefault:
5455
type: geometric::RRTstar
5556
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)
@@ -88,8 +89,6 @@ jaco_arm:
8889
- PRMkConfigDefault
8990
- PRMstarkConfigDefault
9091
hand:
91-
enforce_constrained_state_space: true
92-
projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2)
9392
planner_configs:
9493
- SBLkConfigDefault
9594
- ESTkConfigDefault

ada_moveit/launch/demo.launch.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -261,7 +261,9 @@ def generate_launch_description():
261261
package="controller_manager",
262262
executable="ros2_control_node",
263263
parameters=[robot_description, robot_controllers],
264-
arguments=["--ros-args", "--log-level", log_level],
264+
# Commented out the log-level since the joint state publisher logs every joint read
265+
# when on debug level
266+
arguments=["--ros-args"],#, "--log-level", log_level],
265267
)
266268
)
267269

0 commit comments

Comments
 (0)