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
00042 #include <ros/ros.h>
00043 #include <sensor_msgs/PointCloud2.h>
00044 #include <visualization_msgs/Marker.h>
00045 #include <pcl/point_types.h>
00046
00047 #include <table_objects/GetObjects.h>
00048
00049 ros::ServiceClient client;
00050 ros::Publisher pub;
00051 ros::Publisher pub_marker;
00052
00053 void callback (sensor_msgs::PointCloud2 cloud)
00054 {
00055 table_objects::GetObjects srv;
00056 srv.request.data = cloud;
00057 if (client.call(srv))
00058 {
00059
00060 for (size_t i = 0; i < srv.response.table_objects.size (); i++)
00061 {
00062 mapping_msgs::CollisionObject obj = srv.response.table_objects[i];
00063
00064 pub.publish (obj);
00065
00066
00067 visualization_msgs::Marker marker;
00068 marker.header = obj.header;
00069 marker.ns = "CollisionObjects";
00070 marker.id = i;
00071 marker.type = visualization_msgs::Marker::CUBE;
00072 marker.action = visualization_msgs::Marker::ADD;
00073 marker.pose.position = obj.poses[0].position;
00074 marker.pose.orientation = obj.poses[0].orientation;
00075 marker.scale.x = obj.shapes[0].dimensions[0];
00076 marker.scale.y = obj.shapes[0].dimensions[1];
00077 marker.scale.z = obj.shapes[0].dimensions[2];
00078 marker.color.a = 0.5;
00079 marker.color.r = 0.5;
00080 marker.color.g = 0.5;
00081 marker.color.b = 0.5;
00082 pub_marker.publish (marker);
00083 }
00084 ROS_INFO("Published %zu objects", srv.response.table_objects.size ());
00085 }
00086 else
00087 ROS_ERROR("Failed to call service!");
00088 }
00089
00090
00091 int
00092 main (int argc, char** argv)
00093 {
00094 ros::init (argc, argv, "test_table_objects");
00095
00096 ros::NodeHandle nh;
00097
00098 client = nh.serviceClient<table_objects::GetObjects>("get_table_objects");
00099
00100 pub = nh.advertise<mapping_msgs::CollisionObject> ("collison_objects", 50);
00101 pub_marker = nh.advertise<visualization_msgs::Marker> ("collison_object_markers", 50);
00102
00103 ros::Subscriber sub = nh.subscribe("/extract_objects_indices/output", 5, callback);
00104
00105 ros::spin ();
00106
00107 return (0);
00108 }