Setup Robot Tutorial¶
Overview¶
The dual arm capability can be used on a new robot “robotX” by updating the existing “robotX_moveit_config” package. For this tutorial robotX will be the pr2 robot.
Pre-requisites¶
MoveIt! and ROS
- Follow the instructions for installing MoveIt! first, if you not already done that.
- Setup MoveIt! for your robot.
- Installed the code for the Moveit dual arm planning
Configure moveit_config package¶
The configuration of the robot to use the dual arm capability requires only minor updates in the config package and the creation of a yaml file holding specific parameters for the dual arm planning.
First, open the ‘pr2.srdf’ file in the config directory of you pr2_moveit_config package. Inside this file check if there are groups defined for both arms and both arms + torso (it depends if you plan to use the torso). If this/these group(s) does not exist you must create it/them. As for an example.
<group name="arms"> <group name="left_arm" /> <group name="right_arm" /> </group> <group name="arms_torso"> <group name="arms" /> <group name="torso" /> </group>
Next, open ‘ompl_planning.yaml’ and define a new configuration for a planner in order to use the DualArmGeometricPlanningContext. It is important to write the plugin field.
RRTConnectkConfigDualArm: plugin: ompl_interface/DualArmGeometricPlanningContext type: geometric::RRTConnectCustom range: 0.5
Then, the first file to create is a YAML configuration file (call it dual_arm_manipulation.yaml and place it in the config directory of your MoveIt! config directory). This will specify the dual_arm configuration for your robot. Here’s an example file for configuring the dual arm capability
dual_arm_manipulation: # Group (torso + arms) name used for the manipulation (from the srdf file) dual_arms_torso_group_name: arms_torso # Group (arms) name used for the manipulation (from srdf file) dual_arms_group_name: arms # Sub groups name used for the manipulation (from the srdf file) torso_name: torso left_arm_name: left_arm right_arm_name: right_arm # End effectors group name # If no end effectors are declared in srdf file put "none" as eef_name left_eef_name: left_eef right_eef_name: right_eef # Tip frames of the arm for the k-solvers l_arm_ksolver_tip_frame: l_wrist_roll_link r_arm_ksolver_tip_frame: r_wrist_roll_link #### To get easily the transforms used to update the state of the robot after sampling # Link names left_arm_base_link: torso_lift_link right_arm_base_link: torso_lift_link arms_torso_parent_link: base_link #### Goal sampling goal_sampling_attempts: 100
Then go to the launch directory of your pr2_moveit_config package and open move_group.launch. Then add these lines in order to load the on the ROS server the variables defined in the previous created file:
<!-- Load parameters for dual arm manipulation --> <rosparam command="load" file="$(find moveit_dual_arm_planning_tutorials)/config/dual_arm_manipulation.yaml"/>
Next, in the same file and inside the move_group node block, add these lines in order to define the constraint sampler which will be used to sample states respecting the dual arm constraints
<!-- Register the dual arm constraint sampler --> <param name="constraint_samplers" value="dual_arm_constraint_sampler::DualArmConstraintSamplerAllocator"/>
In the same launch file and node block, add “move_group/MoveGroupDualArmPickPlaceAction” to the “capabilities” param in order to load the dual arm capability and start its servers when MoveIt! start
<param name="capabilities" value=" move_group/MoveGroupCartesianPathService ... move_group/ClearOctomapService move_group/MoveGroupDualArmPickPlaceAction " />
Congratulations!! - You are now done setting the configuration files to use the duall arm capability with MoveIt!
What’s Next¶
The dual arm pick and place action. Now you need to write the code to use the dual arm pick and place actions to play with MoveIt! using the
- MoveIt! Dual Arm Pick Place with the c++ interface.
- YOYO:TODO:MoveIt! Dual Arm Pick Place with the python interface.