Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00038 #include <geometric_shapes/solid_primitive_dims.h>
00039
00040 static const std::string ROBOT_DESCRIPTION = "robot_description";
00041
00042 void sendKnife()
00043 {
00044 ros::NodeHandle nh;
00045 ros::Publisher pub_aco = nh.advertise<moveit_msgs::AttachedCollisionObject>("attached_collision_object", 10);
00046
00047 moveit_msgs::AttachedCollisionObject aco;
00048 aco.link_name = "r_wrist_roll_link";
00049 aco.touch_links.push_back("r_wrist_roll_link");
00050 aco.touch_links.push_back("r_gripper_palm_link");
00051 aco.touch_links.push_back("r_gripper_led_frame");
00052 aco.touch_links.push_back("r_gripper_motor_accelerometer_link");
00053 aco.touch_links.push_back("r_gripper_tool_frame");
00054 aco.touch_links.push_back("r_gripper_motor_slider_link");
00055 aco.touch_links.push_back("r_gripper_motor_screw_link");
00056 aco.touch_links.push_back("r_gripper_l_finger_link");
00057 aco.touch_links.push_back("r_gripper_l_finger_tip_link");
00058 aco.touch_links.push_back("r_gripper_r_finger_link");
00059 aco.touch_links.push_back("r_gripper_r_finger_tip_link");
00060 aco.touch_links.push_back("r_gripper_l_finger_tip_frame");
00061
00062 moveit_msgs::CollisionObject& co = aco.object;
00063 co.id = "knife";
00064 co.header.stamp = ros::Time::now();
00065 co.header.frame_id = aco.link_name;
00066 co.operation = moveit_msgs::CollisionObject::ADD;
00067 co.primitives.resize(1);
00068 co.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
00069 co.primitives[0].dimensions.push_back(0.1);
00070 co.primitives[0].dimensions.push_back(0.1);
00071 co.primitives[0].dimensions.push_back(0.4);
00072 co.primitive_poses.resize(1);
00073 co.primitive_poses[0].position.x = 0.1;
00074 co.primitive_poses[0].position.y = 0;
00075 co.primitive_poses[0].position.z = -0.2;
00076 co.primitive_poses[0].orientation.w = 1.0;
00077
00078 pub_aco.publish(aco);
00079 sleep(1);
00080 pub_aco.publish(aco);
00081 ROS_INFO("Object published.");
00082 ros::Duration(1.5).sleep();
00083 }
00084
00085 int main(int argc, char** argv)
00086 {
00087 ros::init(argc, argv, "demo", ros::init_options::AnonymousName);
00088
00089 ros::AsyncSpinner spinner(1);
00090 spinner.start();
00091
00092 sendKnife();
00093
00094 ros::waitForShutdown();
00095
00096 return 0;
00097 }