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
00032 #ifndef _RVIZ_MARKERS_HPP_
00033 #define _RVIZ_MARKERS_HPP_
00034
00035 #include <pointcloud_segmentation/rviz_markers.h>
00036
00039 template <class T>
00040 std::string to_string (const T& t)
00041 {
00042 std::stringstream ss;
00043 ss << t;
00044 return ss.str();
00045 };
00047
00048 template <class T>
00049 visualization_msgs::Marker markers<T>::unmark(std::string frame_id, std::string ns, int id)
00050 {
00051 uint32_t shape = visualization_msgs::Marker::CUBE;
00052 visualization_msgs::Marker marker;
00053 marker.header.frame_id = frame_id;
00054 marker.header.stamp = ros::Time::now();
00055
00056 marker.pose.position.x = 100;
00057 marker.pose.position.y = 100;
00058 marker.pose.position.z = 100;
00059 marker.pose.orientation.x = 0.0;
00060 marker.pose.orientation.y = 0.0;
00061 marker.pose.orientation.z = 0.0;
00062 marker.pose.orientation.w = 1.0;
00063
00064 marker.scale.x = 0.1;
00065 marker.scale.y = 0.1;
00066 marker.scale.z = 0.1;
00067
00068 marker.color.r = 1.0f;
00069 marker.color.g = 0.0f;
00070 marker.color.b = 0.0f;
00071 marker.color.a = 0.5;
00072
00073 marker.ns = ns;
00074 marker.id = id;
00075 marker.type = shape;
00076 marker.action = visualization_msgs::Marker::ADD;
00077 marker.lifetime = ros::Duration();
00078 return marker;
00079 };
00081
00082 template <class T>
00083 visualization_msgs::Marker markers<T>::mark(typename PointCloud<T>::Ptr cloud_cluster, string ns ,int id, float r, float g, float b)
00084 {
00085 Eigen::Vector4f centroid;
00086 Eigen::Vector4f min;
00087 Eigen::Vector4f max;
00088
00089 compute3DCentroid (*cloud_cluster, centroid);
00090 getMinMax3D (*cloud_cluster, min, max);
00091
00092 uint32_t shape = visualization_msgs::Marker::CUBE;
00093 visualization_msgs::Marker marker;
00094 marker.header.frame_id = cloud_cluster->header.frame_id;
00095 marker.header.stamp = ros::Time::now();
00096
00097 marker.ns = ns;
00098 marker.id = id;
00099 marker.type = shape;
00100 marker.action = visualization_msgs::Marker::ADD;
00101
00102 marker.pose.position.x = centroid[0];
00103 marker.pose.position.y = centroid[1];
00104 marker.pose.position.z = centroid[2];
00105 marker.pose.orientation.x = 0.0;
00106 marker.pose.orientation.y = 0.0;
00107 marker.pose.orientation.z = 0.0;
00108 marker.pose.orientation.w = 1.0;
00109
00110 marker.scale.x = (max[0]-min[0]);
00111 marker.scale.y = (max[1]-min[1]);
00112 marker.scale.z = (max[2]-min[2]);
00113
00114 if (marker.scale.x ==0)
00115 marker.scale.x=0.1;
00116
00117 if (marker.scale.y ==0)
00118 marker.scale.y=0.1;
00119
00120 if (marker.scale.z ==0)
00121 marker.scale.z=0.1;
00122
00123 marker.color.r = r;
00124 marker.color.g = g;
00125 marker.color.b = b;
00126 marker.color.a = 0.3;
00127
00128 marker.lifetime = ros::Duration();
00129
00130 return marker;
00131 };
00133
00134 template<class T>
00135 visualization_msgs::Marker markers<T>::mark_text(typename PointCloud<T>::Ptr cloud_cluster, string ns ,int id, float r, float g, float b)
00136 {
00137 Eigen::Vector4f centroid;
00138 Eigen::Vector4f min;
00139 Eigen::Vector4f max;
00140
00141 compute3DCentroid (*cloud_cluster, centroid);
00142 pcl::getMinMax3D (*cloud_cluster, min, max);
00143
00144 uint32_t shape = visualization_msgs::Marker::TEXT_VIEW_FACING;
00145 visualization_msgs::Marker marker;
00146 marker.header.frame_id = cloud_cluster->header.frame_id;
00147 marker.header.stamp = ros::Time::now();
00148
00149 marker.ns = ns;
00150 marker.id = id;
00151 marker.type = shape;
00152 marker.action = visualization_msgs::Marker::ADD;
00153
00154 marker.pose.position.x = centroid[0];
00155 marker.pose.position.y = centroid[1];
00156 marker.pose.position.z = max[2]+0.2;
00157
00158 marker.scale.z = 0.4;
00159 marker.color.r = r;
00160 marker.color.g = g;
00161 marker.color.b = b;
00162 marker.color.a = 1.0;
00163
00164
00165 string text;
00166 text = "Cluster" + to_string(id) + "\n X=" + to_string(round(centroid[0])) + ", Y=" + to_string(round(centroid[1])) + ", Z=" + to_string(round(centroid[2])) ;
00167 marker.text=text;
00168 marker.lifetime = ros::Duration();
00169 return marker;
00170 };
00172
00173 #endif