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/o2r 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>
50 #include <OGRE/OgreSceneManager.h>
51 #include <OGRE/OgreSceneNode.h>
52 #endif
53 
54 namespace jsk_rviz_plugins
55 {
56 
57  template <class 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 
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  return false;
130  }
131  return true;
132  }
133 
134  void allocateShapes(int num)
135  {
136  if (num > shapes_.size()) {
137  for (size_t i = shapes_.size(); i < num; i++) {
138  ShapePtr shape (new rviz::Shape(
140  this->scene_node_));
141  shapes_.push_back(shape);
142  }
143  }
144  else if (num < shapes_.size())
145  {
146  shapes_.resize(num);
147  }
148  }
149 
151  {
152  if (num > edges_.size()) {
153  for (size_t i = edges_.size(); i < num; i++) {
154  BillboardLinePtr line(new rviz::BillboardLine(
155  this->context_->getSceneManager(), this->scene_node_));
156  edges_.push_back(line);
157  }
158  }
159  else if (num < edges_.size())
160  {
161  edges_.resize(num); // ok??
162  }
163  }
164 
165  void allocateCoords(int num)
166  {
167  if (num > coords_objects_.size()) {
168  for (size_t i = coords_objects_.size(); i < num; i++) {
169  Ogre::SceneNode* scene_node = this->scene_node_->createChildSceneNode();
170  std::vector<ArrowPtr> coord;
171  for (int i = 0; i < 3; i++) {
172  ArrowPtr arrow (new rviz::Arrow(this->scene_manager_, scene_node));
173  coord.push_back(arrow);
174  }
175  coords_nodes_.push_back(scene_node);
176  coords_objects_.push_back(coord);
177  }
178  }
179  else if (num < coords_objects_.size()) {
180  for (size_t i = num; i < coords_objects_.size(); i++) {
181  // coords_nodes_[i];
182  // coords_objects_[i][0]->setVisible(false);
183  // coords_objects_[i][1]->setVisible(false);
184  // coords_objects_[i][2]->setVisible(false);
185  coords_nodes_[i]->setVisible(false);
186  }
187  coords_objects_.resize(num);
188  coords_nodes_.resize(num);
189  }
190  }
191 
192  void showBoxes(
193  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
194  {
195  edges_.clear();
196  allocateShapes(msg->boxes.size());
197  float min_value = DBL_MAX;
198  float max_value = -DBL_MAX;
199  for (size_t i = 0; i < msg->boxes.size(); i++) {
200  min_value = std::min(min_value, msg->boxes[i].value);
201  max_value = std::max(max_value, msg->boxes[i].value);
202  }
203  for (size_t i = 0; i < msg->boxes.size(); i++) {
204  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
205  if (!isValidBoundingBox(box)) {
206  ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
207  box.dimensions.x, box.dimensions.y, box.dimensions.z);
208  continue;
209  }
210 
211  ShapePtr shape = shapes_[i];
212  Ogre::Vector3 position;
213  Ogre::Quaternion orientation;
214  if(!this->context_->getFrameManager()->transform(
215  box.header, box.pose, position, orientation)) {
216  std::ostringstream oss;
217  oss << "Error transforming pose";
218  oss << " from frame '" << box.header.frame_id << "'";
219  oss << " to frame '" << qPrintable(this->fixed_frame_) << "'";
220  ROS_ERROR_STREAM(oss.str());
221  this->setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
222  return;
223  }
224 
225  // Ogre::Vector3 p(box.pose.position.x,
226  // box.pose.position.y,
227  // box.pose.position.z);
228  // Ogre::Quaternion q(box.pose.orientation.w,
229  // box.pose.orientation.x,
230  // box.pose.orientation.y,
231  // box.pose.orientation.z);
232  shape->setPosition(position);
233  shape->setOrientation(orientation);
234  Ogre::Vector3 dimensions;
235  dimensions[0] = box.dimensions.x;
236  dimensions[1] = box.dimensions.y;
237  dimensions[2] = box.dimensions.z;
238  shape->setScale(dimensions);
239  QColor color = getColor(i, box, min_value, max_value);
240  shape->setColor(color.red() / 255.0,
241  color.green() / 255.0,
242  color.blue() / 255.0,
243  alpha_);
244  }
245  }
246 
247  void showEdges(
248  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
249  {
250  shapes_.clear();
251  allocateBillboardLines(msg->boxes.size());
252  float min_value = DBL_MAX;
253  float max_value = -DBL_MAX;
254  for (size_t i = 0; i < msg->boxes.size(); i++) {
255  min_value = std::min(min_value, msg->boxes[i].value);
256  max_value = std::max(max_value, msg->boxes[i].value);
257  }
258 
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  ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
263  box.dimensions.x, box.dimensions.y, box.dimensions.z);
264  continue;
265  }
266 
267  geometry_msgs::Vector3 dimensions = box.dimensions;
268 
269  BillboardLinePtr edge = edges_[i];
270  edge->clear();
271  Ogre::Vector3 position;
272  Ogre::Quaternion quaternion;
273  if(!this->context_->getFrameManager()->transform(box.header, box.pose,
274  position,
275  quaternion)) {
276  std::ostringstream oss;
277  oss << "Error transforming pose";
278  oss << " from frame '" << box.header.frame_id << "'";
279  oss << " to frame '" << qPrintable(this->fixed_frame_) << "'";
280  ROS_ERROR_STREAM(oss.str());
281  this->setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
282  return;
283  }
284  edge->setPosition(position);
285  edge->setOrientation(quaternion);
286 
287  edge->setMaxPointsPerLine(2);
288  edge->setNumLines(12);
289  edge->setLineWidth(line_width_);
290  QColor color = getColor(i, box, min_value, max_value);
291  edge->setColor(color.red() / 255.0,
292  color.green() / 255.0,
293  color.blue() / 255.0,
294  alpha_);
295 
296  Ogre::Vector3 A, B, C, D, E, F, G, H;
297  A[0] = dimensions.x / 2.0;
298  A[1] = dimensions.y / 2.0;
299  A[2] = dimensions.z / 2.0;
300  B[0] = - dimensions.x / 2.0;
301  B[1] = dimensions.y / 2.0;
302  B[2] = dimensions.z / 2.0;
303  C[0] = - dimensions.x / 2.0;
304  C[1] = - dimensions.y / 2.0;
305  C[2] = dimensions.z / 2.0;
306  D[0] = dimensions.x / 2.0;
307  D[1] = - dimensions.y / 2.0;
308  D[2] = dimensions.z / 2.0;
309 
310  E[0] = dimensions.x / 2.0;
311  E[1] = dimensions.y / 2.0;
312  E[2] = - dimensions.z / 2.0;
313  F[0] = - dimensions.x / 2.0;
314  F[1] = dimensions.y / 2.0;
315  F[2] = - dimensions.z / 2.0;
316  G[0] = - dimensions.x / 2.0;
317  G[1] = - dimensions.y / 2.0;
318  G[2] = - dimensions.z / 2.0;
319  H[0] = dimensions.x / 2.0;
320  H[1] = - dimensions.y / 2.0;
321  H[2] = - dimensions.z / 2.0;
322 
323  edge->addPoint(A); edge->addPoint(B); edge->newLine();
324  edge->addPoint(B); edge->addPoint(C); edge->newLine();
325  edge->addPoint(C); edge->addPoint(D); edge->newLine();
326  edge->addPoint(D); edge->addPoint(A); edge->newLine();
327  edge->addPoint(E); edge->addPoint(F); edge->newLine();
328  edge->addPoint(F); edge->addPoint(G); edge->newLine();
329  edge->addPoint(G); edge->addPoint(H); edge->newLine();
330  edge->addPoint(H); edge->addPoint(E); edge->newLine();
331  edge->addPoint(A); edge->addPoint(E); edge->newLine();
332  edge->addPoint(B); edge->addPoint(F); edge->newLine();
333  edge->addPoint(C); edge->addPoint(G); edge->newLine();
334  edge->addPoint(D); edge->addPoint(H);
335  }
336  }
337 
339  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
340  {
341  allocateCoords(msg->boxes.size());
342  for (size_t i = 0; i < msg->boxes.size(); i++) {
343  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
344  std::vector<ArrowPtr> coord = coords_objects_[i];
345 
346  Ogre::SceneNode* scene_node = coords_nodes_[i];
347  scene_node->setVisible(true);
348  Ogre::Vector3 position;
349  Ogre::Quaternion orientation;
350  if(!this->context_->getFrameManager()->getTransform(
351  box.header, position, orientation)) {
352  ROS_DEBUG("Error transforming from frame '%s' to frame '%s'",
353  box.header.frame_id.c_str(), qPrintable(this->fixed_frame_));
354  return;
355  }
356  scene_node->setPosition(position);
357  scene_node->setOrientation(orientation); // scene node is at frame pose
358 
359  float color[3][3] = {{1, 0, 0},
360  {0, 1, 0},
361  {0, 0, 1}};
362  for (int j = 0; j < 3; j++) {
363  // check radius diraction
364  Ogre::Vector3 scale;
365  if (color[j][0] == 1) {
366  scale = Ogre::Vector3(
367  box.dimensions.x,
368  std::min(box.dimensions.y, box.dimensions.z),
369  std::min(box.dimensions.y, box.dimensions.z));
370  }
371  if (color[j][1] == 1) {
372  scale = Ogre::Vector3(
373  box.dimensions.y,
374  std::min(box.dimensions.x, box.dimensions.z),
375  std::min(box.dimensions.x, box.dimensions.z));
376  }
377  if (color[j][2] == 1) {
378  scale = Ogre::Vector3(
379  box.dimensions.z,
380  std::min(box.dimensions.x, box.dimensions.y),
381  std::min(box.dimensions.x, box.dimensions.y));
382  }
383 
384  Ogre::Vector3 direction(color[j][0], color[j][1], color[j][2]);
385  Ogre::Vector3 pos(box.pose.position.x,
386  box.pose.position.y,
387  box.pose.position.z);
388  Ogre::Quaternion qua(box.pose.orientation.w,
389  box.pose.orientation.x,
390  box.pose.orientation.y,
391  box.pose.orientation.z);
392  direction = qua * direction;
393  Ogre::ColourValue rgba;
394  rgba.a = 1;
395  rgba.r = color[j][0];
396  rgba.g = color[j][1];
397  rgba.b = color[j][2];
398 
399  ArrowPtr arrow = coords_objects_[i][j];
400  arrow->setPosition(pos);
401  arrow->setDirection(direction);
402  arrow->setScale(scale);
403  arrow->setColor(rgba);
404  }
405  }
406  }
407 
408  void hideCoords()
409  {
410  for (size_t i = 0; i < coords_nodes_.size(); i++) {
411  coords_nodes_[i]->setVisible(false);
412  }
413  }
414 
415  }; // class BoundingBoxDisplayCommon
416 
417 } // namespace jsk_rviz_plugins
418 
419 #endif // JSK_RVIZ_PLUGINS_BOUDNING_BOX_DISPLAY_COMMON_H_
std_msgs::ColorRGBA heatColor(double v)
bool isValidBoundingBox(const jsk_recognition_msgs::BoundingBox box_msg)
#define ROS_WARN_THROTTLE(rate,...)
pos
DisplayContext * context_
QColor getColor(size_t index, const jsk_recognition_msgs::BoundingBox &box, double min_value, double max_value)
Ogre::SceneNode * scene_node_
boost::shared_ptr< rviz::BillboardLine > BillboardLinePtr
QString fixed_frame_
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
virtual FrameManager * getFrameManager() const =0
Ogre::SceneManager * scene_manager_
virtual Ogre::SceneManager * getSceneManager() const =0
void showCoords(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &msg)
void showBoxes(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &msg)
std_msgs::ColorRGBA colorCategory20(int i)
void showEdges(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &msg)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
#define ROS_ERROR_STREAM(args)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
std::vector< std::vector< ArrowPtr > > coords_objects_
#define ROS_DEBUG(...)


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sat Mar 20 2021 03:03:18