Go to the documentation of this file.00001
00002 #include <ros/ros.h>
00003
00004 #include <mapping_msgs/CollisionObject.h>
00005 #include <geometric_shapes_msgs/Shape.h>
00006
00007 int main(int argc, char** argv) {
00008
00009 ros::init(argc, argv, "addCylinder");
00010
00011 ros::NodeHandle nh;
00012
00013 ros::Publisher object_in_map_pub_;
00014 object_in_map_pub_ = nh.advertise<mapping_msgs::CollisionObject>("collision_object", 10);
00015
00016 ros::Duration(2.0).sleep();
00017
00018
00019 mapping_msgs::CollisionObject cylinder_object;
00020 cylinder_object.id = "pole";
00021 cylinder_object.operation.operation = mapping_msgs::CollisionObjectOperation::ADD;
00022 cylinder_object.header.frame_id = "base_link";
00023 cylinder_object.header.stamp = ros::Time::now();
00024 geometric_shapes_msgs::Shape object;
00025 object.type = geometric_shapes_msgs::Shape::CYLINDER;
00026 object.dimensions.resize(2);
00027 object.dimensions[0] = .1;
00028 object.dimensions[1] = .75;
00029 geometry_msgs::Pose pose;
00030 pose.position.x = .6;
00031 pose.position.y = -.6;
00032 pose.position.z = .375;
00033 pose.orientation.x = 0;
00034 pose.orientation.y = 0;
00035 pose.orientation.z = 0;
00036 pose.orientation.w = 1;
00037 cylinder_object.shapes.push_back(object);
00038 cylinder_object.poses.push_back(pose);
00039
00040 cylinder_object.id = "pole";
00041 object_in_map_pub_.publish(cylinder_object);
00042
00043 ROS_INFO("Should have published");
00044
00045 ros::Duration(2.0).sleep();
00046
00047 ros::shutdown();
00048 }
00049
00050
00051