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 alpha_min_;
78  double alpha_max_;
79  std::string alpha_method_;
80  double line_width_;
81  double value_threshold_;
82 
83  std::vector<std::vector<ArrowPtr> > coords_objects_;
84  std::vector<Ogre::SceneNode*> coords_nodes_;
85  std::vector<BillboardLinePtr> edges_;
86  std::vector<ShapePtr> shapes_;
87 
88  QColor getColor(
89  size_t index,
90  const jsk_recognition_msgs::BoundingBox& box,
91  double min_value,
92  double max_value)
93  {
94  if (coloring_method_ == "auto") {
95  std_msgs::ColorRGBA ros_color = jsk_topic_tools::colorCategory20(index);
96  return QColor(ros_color.r * 255.0,
97  ros_color.g * 255.0,
98  ros_color.b * 255.0,
99  ros_color.a * 255.0);
100  }
101  else if (coloring_method_ == "flat") {
102  return color_;
103  }
104  else if (coloring_method_ == "label") {
105  std_msgs::ColorRGBA ros_color = jsk_topic_tools::colorCategory20(box.label);
106  return QColor(ros_color.r * 255.0,
107  ros_color.g * 255.0,
108  ros_color.b * 255.0,
109  ros_color.a * 255.0);
110  }
111  else if (coloring_method_ == "value") {
112  if (min_value != max_value) {
113  std_msgs::ColorRGBA ros_color = jsk_topic_tools::heatColor((box.value - min_value) / (max_value - min_value));
114  return QColor(ros_color.r * 255.0,
115  ros_color.g * 255.0,
116  ros_color.b * 255.0,
117  ros_color.a * 255.0);
118  }
119  }
120  return QColor(255.0, 255.0, 255.0, 255.0);
121  }
122 
123  double getAlpha(const jsk_recognition_msgs::BoundingBox& box)
124  {
125  if (alpha_method_ == "flat") {
126  return alpha_;
127  }
128  else if (alpha_method_ == "value")
129  {
130  return alpha_min_ + box.value * (alpha_max_ - alpha_min_);
131  }
132  ROS_WARN_THROTTLE(10, "unknown alpha method");
133  return 1.0;
134  }
135 
136  bool isValidBoundingBox(
137  const jsk_recognition_msgs::BoundingBox box_msg)
138  {
139  // Check size
140  if (box_msg.dimensions.x < 1.0e-9 ||
141  box_msg.dimensions.y < 1.0e-9 ||
142  box_msg.dimensions.z < 1.0e-9 ||
143  std::isnan(box_msg.dimensions.x) ||
144  std::isnan(box_msg.dimensions.y) ||
145  std::isnan(box_msg.dimensions.z) ||
146  box_msg.header.frame_id.empty()) {
147  return false;
148  }
149  return true;
150  }
151 
152  void allocateShapes(int num)
153  {
154  if (num > shapes_.size()) {
155  for (size_t i = shapes_.size(); i < num; i++) {
156  ShapePtr shape (new rviz::Shape(
158  this->scene_node_));
159  shapes_.push_back(shape);
160  }
161  }
162  else if (num < shapes_.size())
163  {
164  shapes_.resize(num);
165  }
166  }
167 
168  void allocateBillboardLines(int num)
169  {
170  if (num > edges_.size()) {
171  for (size_t i = edges_.size(); i < num; i++) {
173  this->context_->getSceneManager(), this->scene_node_));
174  edges_.push_back(line);
175  }
176  }
177  else if (num < edges_.size())
178  {
179  edges_.resize(num); // ok??
180  }
181  }
182 
183  void allocateCoords(int num)
184  {
185  if (num > coords_objects_.size()) {
186  for (size_t i = coords_objects_.size(); i < num; i++) {
187  Ogre::SceneNode* scene_node = this->scene_node_->createChildSceneNode();
188  std::vector<ArrowPtr> coord;
189  for (int i = 0; i < 3; i++) {
190  ArrowPtr arrow (new rviz::Arrow(this->scene_manager_, scene_node));
191  coord.push_back(arrow);
192  }
193  coords_nodes_.push_back(scene_node);
194  coords_objects_.push_back(coord);
195  }
196  }
197  else if (num < coords_objects_.size()) {
198  for (size_t i = num; i < coords_objects_.size(); i++) {
199  // coords_nodes_[i];
200  // coords_objects_[i][0]->setVisible(false);
201  // coords_objects_[i][1]->setVisible(false);
202  // coords_objects_[i][2]->setVisible(false);
203  coords_nodes_[i]->setVisible(false);
204  }
205  coords_objects_.resize(num);
206  coords_nodes_.resize(num);
207  }
208  }
209 
210  void showBoxes(
211  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
212  {
213  edges_.clear();
214  float min_value = DBL_MAX;
215  float max_value = -DBL_MAX;
216  // filter boxes before drawing
217  std::vector<int> box_indices;
218  std::vector<jsk_recognition_msgs::BoundingBox> boxes;
219  for (size_t i = 0; i < msg->boxes.size(); i++) {
220  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
221  if (isValidBoundingBox(box)) {
222  if (box.value < value_threshold_) {
223  continue;
224  }
225  boxes.push_back(box);
226  box_indices.push_back(i);
227  min_value = std::min(min_value, msg->boxes[i].value);
228  max_value = std::max(max_value, msg->boxes[i].value);
229  }
230  else
231  {
232  ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
233  box.dimensions.x, box.dimensions.y, box.dimensions.z);
234  }
235  }
236 
237  // draw filtered boxes
238  allocateShapes(boxes.size());
239  for (size_t i = 0; i < boxes.size(); i++) {
240  jsk_recognition_msgs::BoundingBox box = boxes[i];
241  ShapePtr shape = shapes_[i];
242  Ogre::Vector3 position;
243  Ogre::Quaternion orientation;
244  if(!this->context_->getFrameManager()->transform(
245  box.header, box.pose, position, orientation)) {
246  std::ostringstream oss;
247  oss << "Error transforming pose";
248  oss << " from frame '" << box.header.frame_id << "'";
249  oss << " to frame '" << qPrintable(this->fixed_frame_) << "'";
250  ROS_ERROR_STREAM(oss.str());
251  this->setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
252  return;
253  }
254 
255  // Ogre::Vector3 p(box.pose.position.x,
256  // box.pose.position.y,
257  // box.pose.position.z);
258  // Ogre::Quaternion q(box.pose.orientation.w,
259  // box.pose.orientation.x,
260  // box.pose.orientation.y,
261  // box.pose.orientation.z);
262  shape->setPosition(position);
263  shape->setOrientation(orientation);
264  Ogre::Vector3 dimensions;
265  dimensions[0] = box.dimensions.x;
266  dimensions[1] = box.dimensions.y;
267  dimensions[2] = box.dimensions.z;
268  shape->setScale(dimensions);
269  QColor color = getColor(box_indices[i], box, min_value, max_value);
270  shape->setColor(color.red() / 255.0,
271  color.green() / 255.0,
272  color.blue() / 255.0,
273  getAlpha(box));
274  }
275  }
276 
277  void showEdges(
278  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
279  {
280  shapes_.clear();
281  float min_value = DBL_MAX;
282  float max_value = -DBL_MAX;
283  // filter boxes before drawing
284  std::vector<int> box_indices;
285  std::vector<jsk_recognition_msgs::BoundingBox> boxes;
286  for (size_t i = 0; i < msg->boxes.size(); i++) {
287  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
288  if (isValidBoundingBox(box)) {
289  if (box.value < value_threshold_) {
290  continue;
291  }
292  boxes.push_back(box);
293  box_indices.push_back(i);
294  min_value = std::min(min_value, msg->boxes[i].value);
295  max_value = std::max(max_value, msg->boxes[i].value);
296  }
297  else
298  {
299  ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
300  box.dimensions.x, box.dimensions.y, box.dimensions.z);
301  }
302  }
303 
304  // draw filtered boxes
305  allocateBillboardLines(boxes.size());
306  for (size_t i = 0; i < boxes.size(); i++) {
307  jsk_recognition_msgs::BoundingBox box = boxes[i];
308  geometry_msgs::Vector3 dimensions = box.dimensions;
309 
310  BillboardLinePtr edge = edges_[i];
311  edge->clear();
312  Ogre::Vector3 position;
313  Ogre::Quaternion quaternion;
314  if(!this->context_->getFrameManager()->transform(box.header, box.pose,
315  position,
316  quaternion)) {
317  std::ostringstream oss;
318  oss << "Error transforming pose";
319  oss << " from frame '" << box.header.frame_id << "'";
320  oss << " to frame '" << qPrintable(this->fixed_frame_) << "'";
321  ROS_ERROR_STREAM(oss.str());
322  this->setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
323  return;
324  }
325  edge->setPosition(position);
326  edge->setOrientation(quaternion);
327 
328  edge->setMaxPointsPerLine(2);
329  edge->setNumLines(12);
330  edge->setLineWidth(line_width_);
331  QColor color = getColor(box_indices[i], box, min_value, max_value);
332  edge->setColor(color.red() / 255.0,
333  color.green() / 255.0,
334  color.blue() / 255.0,
335  getAlpha(box));
336 
337  Ogre::Vector3 A, B, C, D, E, F, G, H;
338  A[0] = dimensions.x / 2.0;
339  A[1] = dimensions.y / 2.0;
340  A[2] = dimensions.z / 2.0;
341  B[0] = - dimensions.x / 2.0;
342  B[1] = dimensions.y / 2.0;
343  B[2] = dimensions.z / 2.0;
344  C[0] = - dimensions.x / 2.0;
345  C[1] = - dimensions.y / 2.0;
346  C[2] = dimensions.z / 2.0;
347  D[0] = dimensions.x / 2.0;
348  D[1] = - dimensions.y / 2.0;
349  D[2] = dimensions.z / 2.0;
350 
351  E[0] = dimensions.x / 2.0;
352  E[1] = dimensions.y / 2.0;
353  E[2] = - dimensions.z / 2.0;
354  F[0] = - dimensions.x / 2.0;
355  F[1] = dimensions.y / 2.0;
356  F[2] = - dimensions.z / 2.0;
357  G[0] = - dimensions.x / 2.0;
358  G[1] = - dimensions.y / 2.0;
359  G[2] = - dimensions.z / 2.0;
360  H[0] = dimensions.x / 2.0;
361  H[1] = - dimensions.y / 2.0;
362  H[2] = - dimensions.z / 2.0;
363 
364  edge->addPoint(A); edge->addPoint(B); edge->newLine();
365  edge->addPoint(B); edge->addPoint(C); edge->newLine();
366  edge->addPoint(C); edge->addPoint(D); edge->newLine();
367  edge->addPoint(D); edge->addPoint(A); edge->newLine();
368  edge->addPoint(E); edge->addPoint(F); edge->newLine();
369  edge->addPoint(F); edge->addPoint(G); edge->newLine();
370  edge->addPoint(G); edge->addPoint(H); edge->newLine();
371  edge->addPoint(H); edge->addPoint(E); edge->newLine();
372  edge->addPoint(A); edge->addPoint(E); edge->newLine();
373  edge->addPoint(B); edge->addPoint(F); edge->newLine();
374  edge->addPoint(C); edge->addPoint(G); edge->newLine();
375  edge->addPoint(D); edge->addPoint(H);
376  }
377  }
378 
379  void showCoords(
380  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
381  {
382  std::vector<jsk_recognition_msgs::BoundingBox> boxes;
383  for (size_t i = 0; i < msg->boxes.size(); i++) {
384  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
385  if (isValidBoundingBox(box)) {
386  boxes.push_back(box);
387  }
388  else
389  {
390  ROS_WARN_THROTTLE(10, "Invalid size of bounding box is included and skipped: [%f, %f, %f]",
391  box.dimensions.x, box.dimensions.y, box.dimensions.z);
392  }
393  }
394  allocateCoords(boxes.size());
395  for (size_t i = 0; i < boxes.size(); i++) {
396  jsk_recognition_msgs::BoundingBox box = boxes[i];
397  std::vector<ArrowPtr> coord = coords_objects_[i];
398 
399  Ogre::SceneNode* scene_node = coords_nodes_[i];
400  scene_node->setVisible(true);
401  Ogre::Vector3 position;
402  Ogre::Quaternion orientation;
403  if(!this->context_->getFrameManager()->getTransform(
404  box.header, position, orientation)) {
405  ROS_DEBUG("Error transforming from frame '%s' to frame '%s'",
406  box.header.frame_id.c_str(), qPrintable(this->fixed_frame_));
407  return;
408  }
409  scene_node->setPosition(position);
410  scene_node->setOrientation(orientation); // scene node is at frame pose
411 
412  float color[3][3] = {{1, 0, 0},
413  {0, 1, 0},
414  {0, 0, 1}};
415  for (int j = 0; j < 3; j++) {
416  // check radius diraction
417  Ogre::Vector3 scale;
418  if (color[j][0] == 1) {
419  scale = Ogre::Vector3(
420  box.dimensions.x,
421  std::min(box.dimensions.y, box.dimensions.z),
422  std::min(box.dimensions.y, box.dimensions.z));
423  }
424  if (color[j][1] == 1) {
425  scale = Ogre::Vector3(
426  box.dimensions.y,
427  std::min(box.dimensions.x, box.dimensions.z),
428  std::min(box.dimensions.x, box.dimensions.z));
429  }
430  if (color[j][2] == 1) {
431  scale = Ogre::Vector3(
432  box.dimensions.z,
433  std::min(box.dimensions.x, box.dimensions.y),
434  std::min(box.dimensions.x, box.dimensions.y));
435  }
436 
437  Ogre::Vector3 direction(color[j][0], color[j][1], color[j][2]);
438  Ogre::Vector3 pos(box.pose.position.x,
439  box.pose.position.y,
440  box.pose.position.z);
441  Ogre::Quaternion qua(box.pose.orientation.w,
442  box.pose.orientation.x,
443  box.pose.orientation.y,
444  box.pose.orientation.z);
445  direction = qua * direction;
446  Ogre::ColourValue rgba;
447  rgba.a = 1;
448  rgba.r = color[j][0];
449  rgba.g = color[j][1];
450  rgba.b = color[j][2];
451 
452  ArrowPtr arrow = coords_objects_[i][j];
453  arrow->setPosition(pos);
454  arrow->setDirection(direction);
455  arrow->setScale(scale);
456  arrow->setColor(rgba);
457  }
458  }
459  }
460 
461  void hideCoords()
462  {
463  for (size_t i = 0; i < coords_nodes_.size(); i++) {
464  coords_nodes_[i]->setVisible(false);
465  }
466  }
467 
468  }; // class BoundingBoxDisplayCommon
469 
470 } // namespace jsk_rviz_plugins
471 
472 #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
jsk_rviz_plugins::BoundingBoxDisplayCommon::alpha_method_
std::string alpha_method_
Definition: bounding_box_display_common.h:143
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:152
jsk_rviz_plugins::BoundingBoxDisplayCommon::showCoords
void showCoords(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &msg)
Definition: bounding_box_display_common.h:443
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:147
jsk_rviz_plugins::BoundingBoxDisplayCommon::isValidBoundingBox
bool isValidBoundingBox(const jsk_recognition_msgs::BoundingBox box_msg)
Definition: bounding_box_display_common.h:200
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:148
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:341
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::alpha_max_
double alpha_max_
Definition: bounding_box_display_common.h:142
jsk_rviz_plugins::BoundingBoxDisplayCommon::edges_
std::vector< BillboardLinePtr > edges_
Definition: bounding_box_display_common.h:149
message_filter_display.h
jsk_rviz_plugins::BoundingBoxDisplayCommon::getAlpha
double getAlpha(const jsk_recognition_msgs::BoundingBox &box)
Definition: bounding_box_display_common.h:187
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:525
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:274
num
num
jsk_rviz_plugins::BoundingBoxDisplayCommon::line_width_
double line_width_
Definition: bounding_box_display_common.h:144
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:247
jsk_rviz_plugins::BoundingBoxDisplayCommon::allocateBillboardLines
void allocateBillboardLines(int num)
Definition: bounding_box_display_common.h:232
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:216
jsk_rviz_plugins::BoundingBoxDisplayCommon::alpha_min_
double alpha_min_
Definition: bounding_box_display_common.h:141
jsk_rviz_plugins
Definition: __init__.py:1
jsk_rviz_plugins::BoundingBoxDisplayCommon::shapes_
std::vector< ShapePtr > shapes_
Definition: bounding_box_display_common.h:150
color_property.h
jsk_rviz_plugins::BoundingBoxDisplayCommon::value_threshold_
double value_threshold_
Definition: bounding_box_display_common.h:145
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 Dec 13 2024 03:49:56