47 moveit_msgs::AttachedCollisionObject aco;
48 aco.link_name =
"r_wrist_roll_link";
49 aco.touch_links.push_back(
"r_wrist_roll_link");
50 aco.touch_links.push_back(
"r_gripper_palm_link");
51 aco.touch_links.push_back(
"r_gripper_led_frame");
52 aco.touch_links.push_back(
"r_gripper_motor_accelerometer_link");
53 aco.touch_links.push_back(
"r_gripper_tool_frame");
54 aco.touch_links.push_back(
"r_gripper_motor_slider_link");
55 aco.touch_links.push_back(
"r_gripper_motor_screw_link");
56 aco.touch_links.push_back(
"r_gripper_l_finger_link");
57 aco.touch_links.push_back(
"r_gripper_l_finger_tip_link");
58 aco.touch_links.push_back(
"r_gripper_r_finger_link");
59 aco.touch_links.push_back(
"r_gripper_r_finger_tip_link");
60 aco.touch_links.push_back(
"r_gripper_l_finger_tip_frame");
62 moveit_msgs::CollisionObject& co = aco.object;
65 co.header.frame_id = aco.link_name;
66 co.pose.orientation.w = 1.0;
67 co.operation = moveit_msgs::CollisionObject::ADD;
68 co.primitives.resize(1);
69 co.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
70 co.primitives[0].dimensions.push_back(0.1);
71 co.primitives[0].dimensions.push_back(0.1);
72 co.primitives[0].dimensions.push_back(0.4);
73 co.primitive_poses.resize(1);
74 co.primitive_poses[0].position.x = 0.1;
75 co.primitive_poses[0].position.y = 0;
76 co.primitive_poses[0].position.z = -0.2;
77 co.primitive_poses[0].orientation.w = 1.0;
86 int main(
int argc,
char** argv)