Skip to content

Commit

Permalink
Add comments + doc strings
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Nov 29, 2023
1 parent a168de3 commit da3252e
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 9 deletions.
16 changes: 9 additions & 7 deletions launch/demo_gazebo.launch
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
<?xml version="1.0"?>
<launch>
<!-- specify the planning pipeline -->
<arg name="pipeline" default="ompl" />
<!-- MoveIt options -->
<arg name="pipeline" default="ompl" doc="Planning pipeline to use with MoveIt"/>

<!-- Panda specific options -->
<!-- Panda options -->
<arg name="load_gripper" default="true" />
<arg name="transmission" default="effort" />

<!-- Gazebo specific options -->
<arg name="gazebo_gui" default="true" />
<arg name="paused" default="false" />
<!-- Gazebo options -->
<arg name="gazebo_gui" default="true" doc="Start Gazebo GUI"/>
<arg name="paused" default="false" doc="Start Gazebo paused"/>

<!-- Launch the gazebo simulator and spawn the robot -->
<include file="$(find franka_gazebo)/launch/panda.launch" pass_all_args="true">
Expand All @@ -17,8 +18,9 @@
<arg name="controller" default="$(arg transmission)_joint_trajectory_controller" />
</include>

<!-- Launch MoveIt -->
<include file="$(dirname)/demo.launch" pass_all_args="true">
<!-- robot description is loaded by gazebo.launch, to enable Gazebo features -->
<!-- robot_description is loaded by gazebo.launch, to enable Gazebo features -->
<arg name="load_robot_description" value="false" />
<!-- MoveItSimpleControllerManager provides ros_control's JointTrajectory controllers
as well as GripperCommand actions -->
Expand Down
2 changes: 1 addition & 1 deletion launch/ompl-chomp_planning_pipeline.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,6 @@
<!-- load chomp config -->
<rosparam command="load" file="$(find panda_moveit_config)/config/chomp_planning.yaml"/>

<!-- override trajectory_initialization_method -->
<!-- override trajectory_initialization_method: Use OMPL-generated trajectory -->
<param name="trajectory_initialization_method" value="fillTrajectory"/>
</launch>
3 changes: 2 additions & 1 deletion launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param name="$(arg robot_description)" command="xacro '$(find franka_description)/robots/panda/panda.urdf.xacro' hand:=$(arg load_gripper) arm_id:=$(arg arm_id)" if="$(arg load_robot_description)" />
<param if="$(arg load_robot_description)" name="$(arg robot_description)"
command="xacro '$(find franka_description)/robots/panda/panda.urdf.xacro' hand:=$(arg load_gripper) arm_id:=$(arg arm_id)" />

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" command="xacro '$(find panda_moveit_config)/config/panda.srdf.xacro' hand:=$(arg load_gripper) arm_id:=$(arg arm_id)" />
Expand Down

0 comments on commit da3252e

Please sign in to comment.