36 #include <jsk_topic_tools/color_utils.h>
49 "color", QColor(25, 255, 0),
50 "color to draw the edges",
54 "alpha value to draw the edges",
58 "line width of the edges",
72 std_msgs::ColorRGBA ros_color = jsk_topic_tools::colorCategory20(index);
73 return QColor(ros_color.r * 255.0,
81 return QColor(255, 255, 255, 255);
145 for (
size_t i =
edges_.size(); i <
num; i++) {
158 const jsk_recognition_msgs::SegmentArray::ConstPtr& msg)
161 for (
size_t i = 0; i <
msg->segments.size(); i++) {
162 jsk_recognition_msgs::Segment edge_msg =
msg->segments[i];
167 geometry_msgs::Pose start_pose_local;
168 geometry_msgs::Pose end_pose_local;
169 start_pose_local.position = edge_msg.start_point;
170 start_pose_local.orientation.w = 1.0;
171 end_pose_local.position = edge_msg.end_point;
172 end_pose_local.orientation.w = 1.0;
174 Ogre::Vector3 start_point;
175 Ogre::Vector3 end_point;
176 Ogre::Quaternion quaternion;
183 "'%s' from frame '%s' to frame '%s'",
184 qPrintable(
getName() ),
msg->header.frame_id.c_str(),
188 edge->addPoint(start_point);
189 edge->addPoint(end_point);
192 edge->setColor(color.red() / 255.0,
193 color.green() / 255.0,
194 color.blue() / 255.0,
200 const jsk_recognition_msgs::SegmentArray::ConstPtr& msg)