Skip to content

Commit

Permalink
update panda config from templates
Browse files Browse the repository at this point in the history
re-generated from MSA with adapted templates
see moveit 99c059f
  • Loading branch information
jschleicher committed Oct 20, 2020
1 parent 2551e93 commit 28ede2a
Show file tree
Hide file tree
Showing 8 changed files with 110 additions and 52 deletions.
5 changes: 5 additions & 0 deletions panda_moveit_config/config/cartesian_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
cartesian_limits:
max_trans_vel: 1
max_trans_acc: 2.25
max_trans_dec: -5
max_rot_vel: 1.57
8 changes: 4 additions & 4 deletions panda_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@ joint_limits:
panda_finger_joint1:
has_velocity_limits: true
max_velocity: 0.1
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 0.1
panda_finger_joint2:
has_velocity_limits: true
max_velocity: 0.1
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 0.1
39 changes: 26 additions & 13 deletions panda_moveit_config/launch/chomp_planning_pipeline.launch.xml
Original file line number Diff line number Diff line change
@@ -1,17 +1,30 @@
<launch>
<!-- CHOMP Plugin for MoveIt! -->
<arg name="planning_plugin" value="chomp_interface/CHOMPPlanner" />
<arg name="start_state_max_bounds_error" value="0.1" />
<!-- CHOMP Plugin for MoveIt -->
<arg name="planning_plugin" value="chomp_interface/CHOMPPlanner" />

<param name="planning_plugin" value="$(arg planning_plugin)" />
<param name="request_adapters" value="
default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints"
/>
<param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
<!-- define capabilites that are loaded on start (space seperated) -->
<arg name="capabilities" default=""/>

<rosparam command="load" file="$(find moveit_resources_panda_moveit_config)/config/chomp_planning.yaml" />
<!-- inhibit capabilites (space seperated) -->
<arg name="disable_capabilities" default=""/>

<arg name="start_state_max_bounds_error" value="0.1" />
<!-- The request adapters (plugins) used when planning.
ORDER MATTERS -->
<arg name="planning_adapters"
value="default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints"
/>

<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)" />
<param name="capabilities" value="$(arg capabilities)" />
<param name="disable_capabilities" value="$(arg disable_capabilities)" />

<rosparam command="load" file="$(find moveit_resources_panda_moveit_config)/config/chomp_planning.yaml" />
</launch>
46 changes: 29 additions & 17 deletions panda_moveit_config/launch/move_group.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,6 @@
<arg name="load_gripper" value="$(arg load_gripper)" />
</include>

<arg name="pipeline" default="ompl" />

<!-- GDB Debug Option -->
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
Expand All @@ -20,15 +18,43 @@
<arg if="$(arg info)" name="command_args" value="--debug" />

<!-- move_group settings -->
<arg name="pipeline" default="ompl" />
<arg name="allow_trajectory_execution" default="true"/>
<arg name="fake_execution" default="false"/>
<arg name="execution_type" default="interpolate"/> <!-- set to 'last point' to skip intermediate trajectory in fake execution -->
<arg name="max_safe_path_cost" default="1"/>
<arg name="jiggle_fraction" default="0.05" />
<arg name="publish_monitored_planning_scene" default="true"/>

<arg name="capabilities" default=""/>
<arg name="disable_capabilities" default=""/>
<!-- load these non-default MoveGroup capabilities (space seperated) -->
<!--
<arg name="capabilities" value="
a_package/AwsomeMotionPlanningCapability
another_package/GraspPlanningPipeline
" />
-->

<!-- inhibit these default MoveGroup capabilities (space seperated) -->
<!--
<arg name="disable_capabilities" value="
move_group/MoveGroupKinematicsService
move_group/ClearOctomapService
" />
-->

<arg name="load_robot_description" default="true" />
<!-- load URDF, SRDF and joint_limits configuration -->
<include file="$(find moveit_resources_panda_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="$(arg load_robot_description)" />
</include>

<!-- Planning Functionality -->
<include ns="move_group" file="$(find moveit_resources_panda_moveit_config)/launch/planning_pipeline.launch.xml">
<arg name="pipeline" value="$(arg pipeline)" />
<param name="capabilities" value="$(arg capabilities)"/>
<param name="disable_capabilities" value="$(arg disable_capabilities)"/>
</include>

<!-- Trajectory Execution Functionality -->
Expand All @@ -37,6 +63,7 @@
<arg name="moveit_controller_manager" value="panda" if="$(eval not arg('fake_execution') and not arg('load_gripper'))"/>
<arg name="moveit_controller_manager" value="panda_gripper" if="$(eval not arg('fake_execution') and arg('load_gripper'))"/>
<arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/>
<arg name="execution_type" value="$(arg execution_type)" />
</include>

<!-- Sensors Functionality -->
Expand All @@ -53,21 +80,6 @@
<param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
<param name="jiggle_fraction" value="$(arg jiggle_fraction)" />

<!-- load these non-default MoveGroup capabilities -->
<!--
<param name="capabilities" value="
a_package/AwsomeMotionPlanningCapability
another_package/GraspPlanningPipeline
" />
-->

<!-- inhibit these default MoveGroup capabilities -->
<!--
<param name="disable_capabilities" value="
move_group/MoveGroupKinematicsService
move_group/ClearOctomapService
" />
-->

<!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->
<param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
Expand Down
29 changes: 19 additions & 10 deletions panda_moveit_config/launch/ompl_planning_pipeline.launch.xml
Original file line number Diff line number Diff line change
@@ -1,23 +1,32 @@
<launch>

<!-- OMPL Plugin for MoveIt! -->
<!-- OMPL Plugin for MoveIt -->
<arg name="planning_plugin" value="ompl_interface/OMPLPlanner" />

<!-- The request adapters (plugins) used when planning with OMPL.
<!-- define capabilites that are loaded on start (space seperated) -->
<arg name="capabilities" default=""/>

<!-- inhibit capabilites (space seperated) -->
<arg name="disable_capabilities" default=""/>

<!-- The request adapters (plugins) used when planning with OMPL.
ORDER MATTERS -->
<arg name="planning_adapters" default="
default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints"
/>
<arg name="planning_adapters"
value="default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/ResolveConstraintFrames
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)" />
<param name="capabilities" value="$(arg capabilities)" />
<param name="disable_capabilities" value="$(arg disable_capabilities)" />

<rosparam command="load" file="$(find moveit_resources_panda_moveit_config)/config/ompl_planning.yaml"/>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,19 +1,28 @@
<launch>

<!-- Pilz Command Planner Plugin for MoveIt! -->
<!-- Pilz Command Planner Plugin for MoveIt -->
<arg name="planning_plugin" value="pilz_industrial_motion_planner::CommandPlanner" />

<!-- The request adapters (plugins) used when planning.
ORDER MATTERS -->
<arg name="planning_adapters" value="" />

<!-- define capabilites that are loaded on start (space seperated) -->
<arg name="capabilities" default=""/>

<!-- inhibit capabilites (space seperated) -->
<arg name="disable_capabilities" default=""/>

<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)" />


<!-- MoveGroup capabilities to load -->
<param name="capabilities" value="pilz_industrial_motion_planner/MoveGroupSequenceAction
<!-- MoveGroup capabilities to load, append sequence capability -->
<param name="capabilities" value="$(arg capabilities)
pilz_industrial_motion_planner/MoveGroupSequenceAction
pilz_industrial_motion_planner/MoveGroupSequenceService
" />
" />
<param name="disable_capabilities" value="$(arg disable_capabilities)" />
</launch>
1 change: 1 addition & 0 deletions panda_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<!-- Load updated joint limits (override information from URDF) -->
<group ns="$(arg robot_description)_planning">
<rosparam command="load" file="$(find moveit_resources_panda_moveit_config)/config/joint_limits.yaml"/>
<rosparam command="load" file="$(find moveit_resources_panda_moveit_config)/config/cartesian_limits.yaml"/>
</group>

<!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace -->
Expand Down
15 changes: 12 additions & 3 deletions panda_moveit_config/launch/planning_pipeline.launch.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,19 @@
<launch>

<!-- This file makes it easy to include different planning pipelines;
It is assumed that all planning pipelines are named XXX_planning_pipeline.launch -->
<!-- This file makes it easy to include different planning pipelines;
It is assumed that all planning pipelines are named XXX_planning_pipeline.launch -->

<arg name="pipeline" default="ompl" />

<include file="$(find moveit_resources_panda_moveit_config)/launch/$(arg pipeline)_planning_pipeline.launch.xml" />
<!-- define capabilites that are loaded on start (space seperated) -->
<arg name="capabilities" default=""/>

<!-- inhibit capabilites (space seperated) -->
<arg name="disable_capabilities" default=""/>

<include file="$(find moveit_resources_panda_moveit_config)/launch/$(arg pipeline)_planning_pipeline.launch.xml">
<arg name="capabilities" value="$(arg capabilities)"/>
<arg name="disable_capabilities" value="$(arg disable_capabilities)"/>
</include>

</launch>

0 comments on commit 28ede2a

Please sign in to comment.