-
Notifications
You must be signed in to change notification settings - Fork 21
CSDA10F Moveit Configuration
The invite_motoman_moveit_config package host the MoveIt! configuration of the Motoman CSDA10F with robotiq (85mm and 140mm stroke) 2-finger adaptive grippers.
The following move groups were configured:
-
csda10f
: Move group of all actuated joints in the CSDA10F robot. -
arms
: Move group of both arms without the torso joint. -
arm_left
: Move group of all the joints in the left arm with the 85mm Robotiq gripper. -
arm_left_with_torso
: Move group of all the joints in the left arm with the 85mm Robotiq gripper and torso. -
arm_right
: Move group of all the joints in the right arm with the 140mm Robotiq gripper. -
arm_right_with_torso
: Move group of all the joints in the right arm with the 140mm Robotiq gripper and torso. -
torso
: Move group with only the torso as actuated joint. -
left_gripper
: Move group representing the left 85mm Robotiq gripper. -
right_gripper
: Move group representing the right 140mm Robotiq gripper.
In order to see the move groups in link level detail, launch the Moveit setup assistant and go through the configuration.
roslaunch invite_motoman_moveit_config setup_assistant.launch
Top left clockwise: csda10f
, arms
, arm_left
, arm_right
The two move groups left_gripper
and right_gripper
contain all the respective joints for each gripper (with adapter plates and sensors), the gripper TCP is configured through virtual links that belong to the arm_left
and arm_right
move groups instead of the grippers one, but this is just how ROS TCP should be configurated.
Both robotiq grippers have configured their TCP through the virtual links arm_left_link_tcp
and arm_right_link_tcp
(defined on the invite_csda10f.xacro file), in case any new TCP needs to be configured keep in mind that the new virtual link representing you tool TCP should be a child of each arm tool_0
link .
left_gripper, right_gripper
-
csda10f
: KDL_kinematics_plugin -
arms
: trac_ik_kinematics_plugin -
arm_left
: trac_ik_kinematics_plugin -
arm_right
: trac_ik_kinematics_plugin -
torso
: KDL_kinematics_plugin
All move groups configured to work with Trac_IK kinematics solver are configured with the parameter solve type to Distance
(see trac-ik_lib for more information on the solve type parameter).
Track_IK is selected since it has proven its superiority over KDL over a different set of robots (including Motoman CSDA10F), specifically on 7 DoF arms used in two-arm robots (i.g. Valkyre, Pr2, Baxter, Robonaut). Currently, it doesn't support mimic joints which makes it impossible to integrate over any move group that uses the torso joint.
Comparison between KDL and Track IK kinematics solvers, for the CSDA10F only a move group containing one arm and the torso joint are considered (Image is taken from traclabs/trac-ik)
NOTE: The comparison of the CSDA10F kinematics solvers was performed with the robot configuration of this package, which was also published to motoman_experimental
The autogenerated self-collision matrix requires some manual changes.
- Collision checking between the
arm_right_link_1_s
andarm_left_link_1_s
should be disabled. - Specific care should be given to the collision checking of the gripper links with other links since some collision checkings should be manually enabled.
For ease of use, some pre-defined positions are hardcoded into the robot Moveit configuration for quick use and planning to them. These positions are robot poses that are frequently called or used, such as home positions for different applications.
To create a custom robot pose launch the setup assistant:
roslaunch invite_motoman_moveit_config setup_assistant.launch
and go to the robot poses tab, as indicated in the following picture, where the names of three already defined poses are also shown.
While developing applications this pre teach robot poses can be easily used with the following code, specifically the MoveGroupInterface::setNamedTarget( "name_of_pre_teach_pose" )
method.
// Select csda10f as move group to operate
moveit::planning_interface::MoveGroupInterface csda10f_move_group("csda10f");
// Set target pose by using the name of one of the pre-teach positions
csda10f_move_group.setNamedTarget("home_arms_folded");
// Perform motion on real robot
csda10f_move_group.move();
Invite-Robotics
-
Tutorials