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 #ifndef _MARKER_GENERATOR_H_
00037 #define _MARKER_GENERATOR_H_
00038
00039 #include <vector>
00040
00041 #include <boost/ptr_container/ptr_vector.hpp>
00042
00043 #include <visualization_msgs/Marker.h>
00044 #include <shape_msgs/Mesh.h>
00045 #include <geometry_msgs/Pose.h>
00046
00047 namespace tabletop_object_detector {
00048
00049 class ModelFitInfo;
00050
00052
00055 class MarkerGenerator {
00056 public:
00058 static visualization_msgs::Marker getTableMarker(float xmin, float xmax, float ymin, float ymax);
00060 template <class PointCloudType>
00061 static visualization_msgs::Marker getCloudMarker(const PointCloudType& cloud);
00063 static visualization_msgs::Marker getFitMarker(const shape_msgs::Mesh &mesh, double rank);
00065 static visualization_msgs::Marker getConvexHullTableMarker(const shape_msgs::Mesh &mesh);
00067 static visualization_msgs::Marker createMarker(std::string frame_id, double duration, double xdim, double ydim, double zdim,
00068 double r, double g, double b, int type, int id, std::string ns, geometry_msgs::Pose pose);
00069 };
00070
00075 template <class PointCloudType>
00076 visualization_msgs::Marker MarkerGenerator::getCloudMarker(const PointCloudType& cloud)
00077 {
00078 static bool first_time = true;
00079 if (first_time) {
00080 srand ( time(NULL) );
00081 first_time = false;
00082 }
00083
00084
00085 visualization_msgs::Marker marker;
00086 marker.action = visualization_msgs::Marker::ADD;
00087 marker.lifetime = ros::Duration();
00088
00089 marker.type = visualization_msgs::Marker::POINTS;
00090 marker.scale.x = 0.002;
00091 marker.scale.y = 0.002;
00092 marker.scale.z = 1.0;
00093
00094 marker.color.r = ((double)rand())/RAND_MAX;
00095 marker.color.g = ((double)rand())/RAND_MAX;
00096 marker.color.b = ((double)rand())/RAND_MAX;
00097 marker.color.a = 1.0;
00098
00099 for(size_t i=0; i<cloud.points.size(); i++) {
00100 geometry_msgs::Point p;
00101 p.x = cloud.points[i].x;
00102 p.y = cloud.points[i].y;
00103 p.z = cloud.points[i].z;
00104 marker.points.push_back(p);
00105 }
00106
00107
00108 return marker;
00109 }
00110
00111
00112 }
00113
00114 #endif