Grasp Execution Demo¶
This package serves as a grasp execution simulator using Moveit2 path planners and the results from our grasp planner. It is recommended that you use scene packages generated by the Workcell Builder . If you are using a robot, make sure you have the moveit config folder ( check out Workcell Initialization for more information about the moveit_config folder)
Package configuration¶
Before running the grasp execution package, make sure that you have a scene package in the workcell/src/scenes/ folder.
Launch file¶
Open the grasp_execution.launch.py file in /workcell/src/easy_manipulation_deployment/grasp_execution/launch/ and change the parameters accordingly
scene_pkg
The name of your scene package
Example:
scene_pkg = 'ur5_robotiq_table'
base_link
The base link of the robot connected to the table surface
Example:
robot_base_link = 'base_link'
grasp_execution_node.cpp¶
Open the grasp_execution.launch.py file in /workcell/src/easy_manipulation_deployment/grasp_execution/src/ and change the parameters accordingly
std::string robot_frame = "base_link";
std::string camera_frame = "camera_frame";
std::string ee_frame = "gripper_base_link";
std::string ee_link = "tool0";
std::string robot_group = "manipulator";
std::vector<std::string> ignore_links{
"gripper_finger1_finger_link",
"gripper_finger1_finger_tip_link",
"gripper_finger1_inner_knuckle_link",
"gripper_finger1_knuckle_link",
"gripper_finger2_finger_link",
"gripper_finger2_finger_tip_link",
"gripper_finger2_inner_knuckle_link",
"gripper_finger2_knuckle_link",
"gripper_base_link"
};
robot_frame
Base link of robot
camera_frame
Base link of camera
ee_frame
Base link of End effector
ee_link
Tip link of end effector
robot_group
Robot group state that is declared in the srdf. for example, in the file ur5_moveit_config/config/ur5.srdf.xacro:
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<group name="manipulator">
<chain base_link="base_link" tip_link="ee_link" />
</group>
the robot_group is then manipulator
ignore_links
The list of links that should be ignored during attach and detach operations. Typically we start with including all end effector links to prevent errors.
Running grasp execution¶
ros2 launch grasp_execution grasp_execution.launch.py
You should then see Rviz launch and the initial workcell scene, with the robot arm at its home state.
Changing the home state¶
To change the home state, you need to first define a robot group state in the srdf. For example,in the file ur5_moveit_config/config/ur5.srdf.xacro:
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="manipulator">
<joint name="elbow_joint" value="2.4345" />
<joint name="shoulder_lift_joint" value="-2.298" />
<joint name="shoulder_pan_joint" value="1.7011" />
<joint name="wrist_1_joint" value="-1.7011" />
<joint name="wrist_2_joint" value="-1.6082" />
<joint name="wrist_3_joint" value="-0.0592" />
</group_state>
Next, based on the group state name, change the initial field in ur5_moveit_config/config/fake_controllers.yaml to your group state home:
controller_names:
- fake_manipulator_controller
fake_manipulator_controller:
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
initial:
manipulator: home