visualizer.cpp
Go to the documentation of this file.
00001 #include <handle_detector/visualizer.h>
00002 
00003 
00004 Visualizer::Visualizer(double marker_lifetime)
00005 {
00006   this->marker_lifetime = marker_lifetime;
00007 }
00008 
00009 MarkerArray Visualizer::createCylinders(const std::vector<CylindricalShell> &list, const std::string &frame)
00010 {
00011   // create and resize a marker array message
00012   MarkerArray marker_array;
00013   marker_array.markers.resize(list.size());
00014 
00015   for (std::size_t i = 0; i < list.size(); i++)
00016   {
00017     // create marker
00018     visualization_msgs::Marker marker;
00019     marker.header.frame_id = frame;
00020     marker.header.stamp = ros::Time::now();
00021 
00022     // namespace and id to give the marker a unique identification
00023     marker.ns = "cylinders_ns";
00024     marker.id = i;
00025 
00026     // how long the marker exists
00027     marker.lifetime = ros::Duration(this->marker_lifetime);
00028 
00029     // type of marker (cylinder)
00030     marker.type = visualization_msgs::Marker::CYLINDER;
00031     marker.action = visualization_msgs::Marker::ADD;
00032 
00033     // marker position
00034     marker.pose.position.x = list[i].getCentroid()(0);
00035     marker.pose.position.y = list[i].getCentroid()(1);
00036     marker.pose.position.z = list[i].getCentroid()(2);
00037 
00038     // marker rotation
00039     geometry_msgs::PoseStamped cylinder_pose_msg;
00040     Eigen::Vector3d axis = list[i].getCurvatureAxis();
00041     Eigen::Vector3d normal = list[i].getNormal();
00042     Eigen::Vector3d perp = normal.cross(axis);
00043     tf::Matrix3x3 rotation_matrix(perp(0), normal(0), axis(0), perp(1), normal(1), axis(1), perp(2), normal(2),
00044                                   axis(2));
00045     tf::Quaternion quaternion;
00046     rotation_matrix.getRotation(quaternion);
00047     tf::Stamped<tf::Transform> cylinder_tf_pose(tf::Transform(quaternion), marker.header.stamp, frame);
00048     tf::poseStampedTFToMsg(cylinder_tf_pose, cylinder_pose_msg);
00049     marker.pose.orientation = cylinder_pose_msg.pose.orientation;
00050 
00051     // marker scale
00052     marker.scale.x = list[i].getRadius() * 2; // diameter in x-direction
00053     marker.scale.y = list[i].getRadius() * 2; // diameter in y-direction
00054     marker.scale.z = list[i].getExtent(); // height
00055 
00056     // marker color and transparency
00057     marker.color.a = 0.3;
00058     marker.color.r = 0;
00059     marker.color.g = 255;
00060     marker.color.b = 255;
00061 
00062     marker_array.markers[i] = marker;
00063   }
00064 
00065   return marker_array;
00066 }
00067 
00068 MarkerArray Visualizer::createHandleNumbers(const std::vector<std::vector<CylindricalShell> > &handles,
00069                                             const std::string &frame)
00070 {
00071   // create and resize a marker array message
00072   MarkerArray marker_array;
00073   marker_array.markers.resize(handles.size() * 2);
00074 
00075   for (std::size_t i = 0; i < handles.size() * 2; i++)
00076   {
00077     visualization_msgs::Marker marker;
00078     marker.header.frame_id = frame;
00079     marker.header.stamp = ros::Time::now();
00080     marker.ns = "handle_numbers";
00081     marker.id = i;
00082     marker.lifetime = ros::Duration(this->marker_lifetime);
00083 
00084     if (i % 2 == 0)
00085     {
00086       marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00087       marker.action = visualization_msgs::Marker::ADD;
00088 
00089       // height of an upper-case "A"
00090       marker.scale.z = 0.03;
00091 
00092       // marker position
00093       marker.pose.position.x = handles[i / 2][0].getCentroid()(0);
00094       marker.pose.position.y = handles[i / 2][0].getCentroid()(1);
00095       marker.pose.position.z = handles[i / 2][0].getCentroid()(2) - 0.06;
00096 
00097       // marker color and transparency
00098       marker.color.a = 1.0;
00099       marker.color.r = 1.0;
00100       marker.color.g = 0.0;
00101       marker.color.b = 0.0;
00102 
00103       // displayed text
00104       marker.text = boost::lexical_cast < std::string > ((i / 2) + 1);
00105     }
00106     else
00107     {
00108       // type of marker (cylinder)
00109       marker.type = visualization_msgs::Marker::CUBE;
00110       marker.action = visualization_msgs::Marker::ADD;
00111 
00112       // height of an upper-case "A"
00113       marker.scale.x = 0.03;
00114       marker.scale.y = 0.03;
00115       marker.scale.z = 0.001;
00116 
00117       // marker position
00118       marker.pose.position.x = marker_array.markers[i - 1].pose.position.x;
00119       marker.pose.position.y = marker_array.markers[i - 1].pose.position.y;
00120       marker.pose.position.z = marker_array.markers[i - 1].pose.position.z + 0.015;
00121 
00122       // marker color and transparency
00123       marker.color.a = 1.0;
00124       marker.color.r = 1.0;
00125       marker.color.g = 1.0;
00126       marker.color.b = 1.0;
00127     }
00128     marker_array.markers[i] = marker;
00129   }
00130 
00131   return marker_array;
00132 }
00133 
00134 void Visualizer::createHandles(const std::vector<std::vector<CylindricalShell> > &handles, const std::string &frame,
00135                                std::vector<MarkerArray> &marker_arrays, MarkerArray &all_handle_markers)
00136 {
00137   marker_arrays.resize(handles.size());
00138   std::vector<CylindricalShell> handle_shells;
00139   int k = 0;
00140 
00141   for (std::size_t i = 0; i < handles.size(); i++)
00142   {
00143     marker_arrays[i] = this->createCylinders(handles[i], frame);
00144     for (int j = 0; j < handles[i].size(); j++)
00145       handle_shells.push_back(handles[i][j]);
00146   }
00147 
00148   all_handle_markers = this->createCylinders(handle_shells, frame);
00149 }


handle_detector
Author(s):
autogenerated on Thu Jun 6 2019 17:36:23