Skip to content
Snippets Groups Projects
Commit 320a27cf authored by Raghavender Sahdev's avatar Raghavender Sahdev Committed by Mike Lautman
Browse files

added STOMP related planning files (#5)

* added STOMP related planning files
* removed CHOMP stuff
parent a2f979aa
No related branches found
No related tags found
No related merge requests found
stomp/panda_arm:
group_name: panda_arm
optimization:
num_timesteps: 60
num_iterations: 40
num_iterations_after_valid: 0
num_rollouts: 30
max_rollouts: 30
initialization_method: 1 #[1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
control_cost_weight: 0.0
task:
noise_generator:
- class: stomp_moveit/NormalDistributionSampling
stddev: [0.05, 0.8, 1.0, 0.8, 0.4, 0.4, 0.4]
cost_functions:
- class: stomp_moveit/CollisionCheck
collision_penalty: 1.0
cost_weight: 1.0
kernel_window_percentage: 0.2
longest_valid_joint_move: 0.05
noisy_filters:
- class: stomp_moveit/JointLimits
lock_start: True
lock_goal: True
- class: stomp_moveit/MultiTrajectoryVisualization
line_width: 0.02
rgb: [255, 255, 0]
marker_array_topic: stomp_trajectories
marker_namespace: noisy
update_filters:
- class: stomp_moveit/PolynomialSmoother
poly_order: 6
- class: stomp_moveit/TrajectoryVisualization
line_width: 0.05
rgb: [0, 191, 255]
error_rgb: [255, 0, 0]
publish_intermediate: True
marker_topic: stomp_trajectory
marker_namespace: optimized
<launch>
<!-- Stomp Plugin for MoveIt! -->
<arg name="planning_plugin" value="stomp_moveit/StompPlannerManager" />
<!-- The request adapters (plugins) ORDER MATTERS -->
<arg name="planning_adapters" value="default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints" />
<arg name="start_state_max_bounds_error" value="0.1" />
<param name="planning_plugin" value="$(arg planning_plugin)" />
<param name="request_adapters" value="$(arg planning_adapters)" />
<param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
<rosparam command="load" file="$(find panda_moveit_config)/config/stomp_planning.yaml"/>
</launch>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment