Skip to content

Commit 130109d

Browse files
committed
Tune parameters
1 parent 9bd50ec commit 130109d

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
@@ -12,9 +12,9 @@ planner_configs:
1212
type: geometric::AnytimePathShortening
1313
shortcut: 1 # Attempt to shortcut all new solution paths
1414
hybridize: 1 # Compute hybrid solution trajectories
15-
max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
15+
max_hybrid_paths: 8 # Number of hybrid paths generated per iteration
1616
num_planners: 4 # The number of default planners to use for planning
17-
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]"
17+
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]"
1818
SBLkConfigDefault:
1919
type: geometric::SBL
2020
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
@@ -46,7 +46,8 @@ planner_configs:
4646
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
4747
RRTConnectkConfigDefault:
4848
type: geometric::RRTConnect
49-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
49+
intermediate_states: 0 # Whether to add intermediate states to the plan, default 0
50+
range: 0.05 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
5051
RRTstarkConfigDefault:
5152
type: geometric::RRTstar
5253
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)
@@ -85,8 +86,6 @@ jaco_arm:
8586
- PRMkConfigDefault
8687
- PRMstarkConfigDefault
8788
hand:
88-
enforce_constrained_state_space: true
89-
projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2)
9089
planner_configs:
9190
- SBLkConfigDefault
9291
- ESTkConfigDefault

ada_moveit/launch/demo.launch.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -250,7 +250,9 @@ def generate_launch_description():
250250
package="controller_manager",
251251
executable="ros2_control_node",
252252
parameters=[robot_description, robot_controllers],
253-
arguments=["--ros-args", "--log-level", log_level],
253+
# Commented out the log-level since the joint state publisher logs every joint read
254+
# when on debug level
255+
arguments=["--ros-args"],#, "--log-level", log_level],
254256
)
255257
)
256258

0 commit comments

Comments
 (0)