bounding_box_display_common.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016, JSK Lab.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef JSK_RVIZ_PLUGINS_BOUDNING_BOX_DISPLAY_COMMON_H_
36 #define JSK_RVIZ_PLUGINS_BOUDNING_BOX_DISPLAY_COMMON_H_
37 
38 #ifndef Q_MOC_RUN
40 #include <jsk_recognition_msgs/BoundingBoxArray.h>
41 #include <jsk_topic_tools/color_utils.h>
50 #include <OGRE/OgreSceneManager.h>
51 #include <OGRE/OgreSceneNode.h>
52 #endif
53 
54 namespace jsk_rviz_plugins
55 {
56 
57  template <class MessageType>
58  class BoundingBoxDisplayCommon: public rviz::MessageFilterDisplay<MessageType>
59  {
60 public:
63 #if ROS_VERSION_MINIMUM(1,12,0)
64  typedef std::shared_ptr<rviz::Shape> ShapePtr;
65  typedef std::shared_ptr<rviz::BillboardLine> BillboardLinePtr;
66  typedef std::shared_ptr<rviz::Arrow> ArrowPtr;
67 #else
71 #endif
72 
73 protected:
74  QColor color_;
75  std::string coloring_method_;
76  double alpha_;
77  double line_width_;
78 
79  std::vector<std::vector<ArrowPtr> > coords_objects_;
80  std::vector<Ogre::SceneNode*> coords_nodes_;
81  std::vector<BillboardLinePtr> edges_;
82  std::vector<ShapePtr> shapes_;
83 
84  QColor getColor(
85  size_t index,
86  const jsk_recognition_msgs::BoundingBox& box,
87  double min_value,
88  double max_value)
89  {
90  if (coloring_method_ == "auto") {
91  std_msgs::ColorRGBA ros_color = jsk_topic_tools::colorCategory20(index);
92  return QColor(ros_color.r * 255.0,
93  ros_color.g * 255.0,
94  ros_color.b * 255.0,
95  ros_color.a * 255.0);
96  }
97  else if (coloring_method_ == "flat") {
98  return color_;
99  }
100  else if (coloring_method_ == "label") {
101  std_msgs::ColorRGBA ros_color = jsk_topic_tools::colorCategory20(box.label);
102  return QColor(ros_color.r * 255.0,
103  ros_color.g * 255.0,
104  ros_color.b * 255.0,
105  ros_color.a * 255.0);
106  }
107  else if (coloring_method_ == "value") {
108  if (min_value != max_value) {
109  std_msgs::ColorRGBA ros_color = jsk_topic_tools::heatColor((box.value - min_value) / (max_value - min_value));
110  return QColor(ros_color.r * 255.0,
111  ros_color.g * 255.0,
112  ros_color.b * 255.0,
113  ros_color.a * 255.0);
114  }
115  }
116  return QColor(255.0, 255.0, 255.0, 255.0);
117  }
118 
119  bool isValidBoundingBox(
120  const jsk_recognition_msgs::BoundingBox box_msg)
121  {
122  // Check size
123  if (box_msg.dimensions.x < 1.0e-9 ||
124  box_msg.dimensions.y < 1.0e-9 ||
125  box_msg.dimensions.z < 1.0e-9 ||
126  std::isnan(box_msg.dimensions.x) ||
127  std::isnan(box_msg.dimensions.y) ||
128  std::isnan(box_msg.dimensions.z) ||
129  box_msg.header.frame_id.empty()) {
130  return false;
131  }
132  return true;
133  }
134 
135  void allocateShapes(int num)
136  {
137  if (num > shapes_.size()) {
138  for (size_t i = shapes_.size(); i < num; i++) {
139  ShapePtr shape (new rviz::Shape(
141  this->scene_node_));
142  shapes_.push_back(shape);
143  }
144  }
145  else if (num < shapes_.size())
146  {
147  shapes_.resize(num);
148  }
149  }
150 
151  void allocateBillboardLines(int num)
152  {
153  if (num > edges_.size()) {
154  for (size_t i = edges_.size(); i < num; i++) {
156  this->context_->getSceneManager(), this->scene_node_));
157  edges_.push_back(line);
158  }
159  }
160  else if (num < edges_.size())
161  {
162  edges_.resize(num); // ok??
163  }
164  }
165 
166  void allocateCoords(int num)
167  {
168  if (num > coords_objects_.size()) {
169  for (size_t i = coords_objects_.size(); i < num; i++) {
170  Ogre::SceneNode* scene_node = this->scene_node_->createChildSceneNode();
171  std::vector<ArrowPtr> coord;
172  for (int i = 0; i < 3; i++) {
173  ArrowPtr arrow (new rviz::Arrow(this->scene_manager_, scene_node));
174  coord.push_back(arrow);
175  }
176  coords_nodes_.push_back(scene_node);
177  coords_objects_.push_back(coord);
178  }
179  }
180  else if (num < coords_objects_.size()) {
181  for (size_t i = num; i < coords_objects_.size(); i++) {
182  // coords_nodes_[i];
183  // coords_objects_[i][0]->setVisible(false);
184  // coords_objects_[i][1]->setVisible(false);
185  // coords_objects_[i][2]->setVisible(false);
186  coords_nodes_[i]->setVisible(false);
187  }
188  coords_objects_.resize(num);
189  coords_nodes_.resize(num);
190  }
191  }
192 
193  void showBoxes(
194  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
195  {
196  edges_.clear();
197  float min_value = DBL_MAX;
198  float max_value = -DBL_MAX;
199  std::vector<jsk_recognition_msgs::BoundingBox> boxes;
200  for (size_t i = 0; i < msg->boxes.size(); i++) {
201  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
202  if (isValidBoundingBox(box)) {
203  boxes.push_back(box);
204  min_value = std::min(min_value, msg->boxes[i].value);
205  max_value = std::max(max_value, msg->boxes[i].value);
206  }
207  else
208  {
209  ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
210  box.dimensions.x, box.dimensions.y, box.dimensions.z);
211  }
212  }
213  allocateShapes(boxes.size());
214  for (size_t i = 0; i < boxes.size(); i++) {
215  jsk_recognition_msgs::BoundingBox box = boxes[i];
216  ShapePtr shape = shapes_[i];
217  Ogre::Vector3 position;
218  Ogre::Quaternion orientation;
219  if(!this->context_->getFrameManager()->transform(
220  box.header, box.pose, position, orientation)) {
221  std::ostringstream oss;
222  oss << "Error transforming pose";
223  oss << " from frame '" << box.header.frame_id << "'";
224  oss << " to frame '" << qPrintable(this->fixed_frame_) << "'";
225  ROS_ERROR_STREAM(oss.str());
226  this->setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
227  return;
228  }
229 
230  // Ogre::Vector3 p(box.pose.position.x,
231  // box.pose.position.y,
232  // box.pose.position.z);
233  // Ogre::Quaternion q(box.pose.orientation.w,
234  // box.pose.orientation.x,
235  // box.pose.orientation.y,
236  // box.pose.orientation.z);
237  shape->setPosition(position);
238  shape->setOrientation(orientation);
239  Ogre::Vector3 dimensions;
240  dimensions[0] = box.dimensions.x;
241  dimensions[1] = box.dimensions.y;
242  dimensions[2] = box.dimensions.z;
243  shape->setScale(dimensions);
244  QColor color = getColor(i, box, min_value, max_value);
245  shape->setColor(color.red() / 255.0,
246  color.green() / 255.0,
247  color.blue() / 255.0,
248  alpha_);
249  }
250  }
251 
252  void showEdges(
253  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
254  {
255  shapes_.clear();
256  float min_value = DBL_MAX;
257  float max_value = -DBL_MAX;
258  std::vector<jsk_recognition_msgs::BoundingBox> boxes;
259  for (size_t i = 0; i < msg->boxes.size(); i++) {
260  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
261  if (isValidBoundingBox(box)) {
262  boxes.push_back(box);
263  min_value = std::min(min_value, msg->boxes[i].value);
264  max_value = std::max(max_value, msg->boxes[i].value);
265  }
266  else
267  {
268  ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
269  box.dimensions.x, box.dimensions.y, box.dimensions.z);
270  }
271  }
272 
273  allocateBillboardLines(boxes.size());
274  for (size_t i = 0; i < boxes.size(); i++) {
275  jsk_recognition_msgs::BoundingBox box = boxes[i];
276  geometry_msgs::Vector3 dimensions = box.dimensions;
277 
278  BillboardLinePtr edge = edges_[i];
279  edge->clear();
280  Ogre::Vector3 position;
281  Ogre::Quaternion quaternion;
282  if(!this->context_->getFrameManager()->transform(box.header, box.pose,
283  position,
284  quaternion)) {
285  std::ostringstream oss;
286  oss << "Error transforming pose";
287  oss << " from frame '" << box.header.frame_id << "'";
288  oss << " to frame '" << qPrintable(this->fixed_frame_) << "'";
289  ROS_ERROR_STREAM(oss.str());
290  this->setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
291  return;
292  }
293  edge->setPosition(position);
294  edge->setOrientation(quaternion);
295 
296  edge->setMaxPointsPerLine(2);
297  edge->setNumLines(12);
298  edge->setLineWidth(line_width_);
299  QColor color = getColor(i, box, min_value, max_value);
300  edge->setColor(color.red() / 255.0,
301  color.green() / 255.0,
302  color.blue() / 255.0,
303  alpha_);
304 
305  Ogre::Vector3 A, B, C, D, E, F, G, H;
306  A[0] = dimensions.x / 2.0;
307  A[1] = dimensions.y / 2.0;
308  A[2] = dimensions.z / 2.0;
309  B[0] = - dimensions.x / 2.0;
310  B[1] = dimensions.y / 2.0;
311  B[2] = dimensions.z / 2.0;
312  C[0] = - dimensions.x / 2.0;
313  C[1] = - dimensions.y / 2.0;
314  C[2] = dimensions.z / 2.0;
315  D[0] = dimensions.x / 2.0;
316  D[1] = - dimensions.y / 2.0;
317  D[2] = dimensions.z / 2.0;
318 
319  E[0] = dimensions.x / 2.0;
320  E[1] = dimensions.y / 2.0;
321  E[2] = - dimensions.z / 2.0;
322  F[0] = - dimensions.x / 2.0;
323  F[1] = dimensions.y / 2.0;
324  F[2] = - dimensions.z / 2.0;
325  G[0] = - dimensions.x / 2.0;
326  G[1] = - dimensions.y / 2.0;
327  G[2] = - dimensions.z / 2.0;
328  H[0] = dimensions.x / 2.0;
329  H[1] = - dimensions.y / 2.0;
330  H[2] = - dimensions.z / 2.0;
331 
332  edge->addPoint(A); edge->addPoint(B); edge->newLine();
333  edge->addPoint(B); edge->addPoint(C); edge->newLine();
334  edge->addPoint(C); edge->addPoint(D); edge->newLine();
335  edge->addPoint(D); edge->addPoint(A); edge->newLine();
336  edge->addPoint(E); edge->addPoint(F); edge->newLine();
337  edge->addPoint(F); edge->addPoint(G); edge->newLine();
338  edge->addPoint(G); edge->addPoint(H); edge->newLine();
339  edge->addPoint(H); edge->addPoint(E); edge->newLine();
340  edge->addPoint(A); edge->addPoint(E); edge->newLine();
341  edge->addPoint(B); edge->addPoint(F); edge->newLine();
342  edge->addPoint(C); edge->addPoint(G); edge->newLine();
343  edge->addPoint(D); edge->addPoint(H);
344  }
345  }
346 
347  void showCoords(
348  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
349  {
350  std::vector<jsk_recognition_msgs::BoundingBox> boxes;
351  for (size_t i = 0; i < msg->boxes.size(); i++) {
352  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
353  if (isValidBoundingBox(box)) {
354  boxes.push_back(box);
355  }
356  else
357  {
358  ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
359  box.dimensions.x, box.dimensions.y, box.dimensions.z);
360  }
361  }
362  allocateCoords(boxes.size());
363  for (size_t i = 0; i < boxes.size(); i++) {
364  jsk_recognition_msgs::BoundingBox box = boxes[i];
365  std::vector<ArrowPtr> coord = coords_objects_[i];
366 
367  Ogre::SceneNode* scene_node = coords_nodes_[i];
368  scene_node->setVisible(true);
369  Ogre::Vector3 position;
370  Ogre::Quaternion orientation;
371  if(!this->context_->getFrameManager()->getTransform(
372  box.header, position, orientation)) {
373  ROS_DEBUG("Error transforming from frame '%s' to frame '%s'",
374  box.header.frame_id.c_str(), qPrintable(this->fixed_frame_));
375  return;
376  }
377  scene_node->setPosition(position);
378  scene_node->setOrientation(orientation); // scene node is at frame pose
379 
380  float color[3][3] = {{1, 0, 0},
381  {0, 1, 0},
382  {0, 0, 1}};
383  for (int j = 0; j < 3; j++) {
384  // check radius diraction
385  Ogre::Vector3 scale;
386  if (color[j][0] == 1) {
387  scale = Ogre::Vector3(
388  box.dimensions.x,
389  std::min(box.dimensions.y, box.dimensions.z),
390  std::min(box.dimensions.y, box.dimensions.z));
391  }
392  if (color[j][1] == 1) {
393  scale = Ogre::Vector3(
394  box.dimensions.y,
395  std::min(box.dimensions.x, box.dimensions.z),
396  std::min(box.dimensions.x, box.dimensions.z));
397  }
398  if (color[j][2] == 1) {
399  scale = Ogre::Vector3(
400  box.dimensions.z,
401  std::min(box.dimensions.x, box.dimensions.y),
402  std::min(box.dimensions.x, box.dimensions.y));
403  }
404 
405  Ogre::Vector3 direction(color[j][0], color[j][1], color[j][2]);
406  Ogre::Vector3 pos(box.pose.position.x,
407  box.pose.position.y,
408  box.pose.position.z);
409  Ogre::Quaternion qua(box.pose.orientation.w,
410  box.pose.orientation.x,
411  box.pose.orientation.y,
412  box.pose.orientation.z);
413  direction = qua * direction;
414  Ogre::ColourValue rgba;
415  rgba.a = 1;
416  rgba.r = color[j][0];
417  rgba.g = color[j][1];
418  rgba.b = color[j][2];
419 
420  ArrowPtr arrow = coords_objects_[i][j];
421  arrow->setPosition(pos);
422  arrow->setDirection(direction);
423  arrow->setScale(scale);
424  arrow->setColor(rgba);
425  }
426  }
427  }
428 
429  void hideCoords()
430  {
431  for (size_t i = 0; i < coords_nodes_.size(); i++) {
432  coords_nodes_[i]->setVisible(false);
433  }
434  }
435 
436  }; // class BoundingBoxDisplayCommon
437 
438 } // namespace jsk_rviz_plugins
439 
440 #endif // JSK_RVIZ_PLUGINS_BOUDNING_BOX_DISPLAY_COMMON_H_
rviz::BillboardLine
rviz::MessageFilterDisplay
jsk_rviz_plugins::BoundingBoxDisplayCommon::ShapePtr
boost::shared_ptr< rviz::Shape > ShapePtr
Definition: bounding_box_display_common.h:126
msg
msg
jsk_rviz_plugins::BoundingBoxDisplayCommon::getColor
QColor getColor(size_t index, const jsk_recognition_msgs::BoundingBox &box, double min_value, double max_value)
Definition: bounding_box_display_common.h:148
jsk_rviz_plugins::BoundingBoxDisplayCommon::showCoords
void showCoords(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &msg)
Definition: bounding_box_display_common.h:411
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
contact_state_marker.scale
scale
Definition: contact_state_marker.py:91
boost::shared_ptr
rviz::Arrow
jsk_rviz_plugins::BoundingBoxDisplayCommon::ArrowPtr
boost::shared_ptr< rviz::Arrow > ArrowPtr
Definition: bounding_box_display_common.h:134
rviz::StatusProperty::Error
Error
tf_diff_text.pos
pos
Definition: tf_diff_text.py:18
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
enum_property.h
jsk_rviz_plugins::BoundingBoxDisplayCommon::~BoundingBoxDisplayCommon
~BoundingBoxDisplayCommon()
Definition: bounding_box_display_common.h:126
jsk_rviz_plugins::BoundingBoxDisplayCommon::coords_objects_
std::vector< std::vector< ArrowPtr > > coords_objects_
Definition: bounding_box_display_common.h:143
jsk_rviz_plugins::BoundingBoxDisplayCommon::isValidBoundingBox
bool isValidBoundingBox(const jsk_recognition_msgs::BoundingBox box_msg)
Definition: bounding_box_display_common.h:183
rviz::Display::fixed_frame_
QString fixed_frame_
shape.h
jsk_rviz_plugins::BoundingBoxDisplayCommon::coords_nodes_
std::vector< Ogre::SceneNode * > coords_nodes_
Definition: bounding_box_display_common.h:144
rviz::DisplayContext::getSceneManager
virtual Ogre::SceneManager * getSceneManager() const=0
float_property.h
billboard_line.h
jsk_rviz_plugins::BoundingBoxDisplayCommon::BoundingBoxDisplayCommon
BoundingBoxDisplayCommon()
Definition: bounding_box_display_common.h:125
rviz::Display::setStatus
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
A
bool_property.h
bounding_box_display_common.h
jsk_rviz_plugins::BoundingBoxDisplayCommon::showEdges
void showEdges(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &msg)
Definition: bounding_box_display_common.h:316
ROS_DEBUG
#define ROS_DEBUG(...)
jsk_rviz_plugins::BoundingBoxDisplayCommon::BillboardLinePtr
boost::shared_ptr< rviz::BillboardLine > BillboardLinePtr
Definition: bounding_box_display_common.h:133
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
jsk_rviz_plugins::BoundingBoxDisplayCommon::edges_
std::vector< BillboardLinePtr > edges_
Definition: bounding_box_display_common.h:145
message_filter_display.h
rviz::Display::scene_manager_
Ogre::SceneManager * scene_manager_
jsk_rviz_plugins::BoundingBoxDisplayCommon::alpha_
double alpha_
Definition: bounding_box_display_common.h:140
arrow.h
jsk_rviz_plugins::BoundingBoxDisplayCommon::hideCoords
void hideCoords()
Definition: bounding_box_display_common.h:493
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const=0
jsk_rviz_plugins::BoundingBoxDisplayCommon::showBoxes
void showBoxes(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &msg)
Definition: bounding_box_display_common.h:257
num
num
jsk_rviz_plugins::BoundingBoxDisplayCommon::line_width_
double line_width_
Definition: bounding_box_display_common.h:141
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
rviz::Display::context_
DisplayContext * context_
jsk_rviz_plugins::BoundingBoxDisplayCommon::allocateCoords
void allocateCoords(int num)
Definition: bounding_box_display_common.h:230
jsk_rviz_plugins::BoundingBoxDisplayCommon::allocateBillboardLines
void allocateBillboardLines(int num)
Definition: bounding_box_display_common.h:215
jsk_rviz_plugins::BoundingBoxDisplayCommon::color_
QColor color_
Definition: bounding_box_display_common.h:138
rviz::Shape
rviz::FrameManager::transform
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
jsk_rviz_plugins::BoundingBoxDisplayCommon::allocateShapes
void allocateShapes(int num)
Definition: bounding_box_display_common.h:199
jsk_rviz_plugins
Definition: __init__.py:1
jsk_rviz_plugins::BoundingBoxDisplayCommon::shapes_
std::vector< ShapePtr > shapes_
Definition: bounding_box_display_common.h:146
color_property.h
jsk_rviz_plugins::BoundingBoxDisplayCommon::coloring_method_
std::string coloring_method_
Definition: bounding_box_display_common.h:139
rviz::Shape::Cube
Cube


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Fri Aug 2 2024 08:50:14