path_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <boost/bind/bind.hpp>
31 
32 #include <OgreSceneNode.h>
33 #include <OgreSceneManager.h>
34 #include <OgreManualObject.h>
35 #include <OgreMatrix4.h>
36 
37 #include <rviz/display_context.h>
38 #include <rviz/frame_manager.h>
44 #include <rviz/validate_floats.h>
46 
49 
50 namespace rviz
51 {
53 {
55  new EnumProperty("Line Style", "Lines", "The rendering operation to use to draw the grid lines.",
57 
58  style_property_->addOption("Lines", LINES);
59  style_property_->addOption("Billboards", BILLBOARDS);
60 
62  "Line Width", 0.03,
63  "The width, in meters, of each path line. Only works with the 'Billboards' style.", this,
67 
68  color_property_ = new ColorProperty("Color", QColor(25, 255, 0), "Color to draw the path.", this);
69 
71  new FloatProperty("Alpha", 1.0, "Amount of transparency to apply to the path.", this);
72 
73  buffer_length_property_ = new IntProperty("Buffer Length", 1, "Number of paths to display.", this,
76 
78  "Offset", Ogre::Vector3::ZERO,
79  "Allows you to offset the path from the origin of the reference frame. In meters.", this,
81 
82  pose_style_property_ = new EnumProperty("Pose Style", "None", "Shape to display the pose as.", this,
87 
88  pose_axes_length_property_ = new rviz::FloatProperty("Length", 0.3, "Length of the axes.", this,
90  pose_axes_radius_property_ = new rviz::FloatProperty("Radius", 0.03, "Radius of the axes.", this,
92 
94  new ColorProperty("Pose Color", QColor(255, 85, 255), "Color to draw the poses.", this,
97  "Shaft Length", 0.1, "Length of the arrow shaft.", this, &PathDisplay::updatePoseArrowGeometry);
99  "Head Length", 0.2, "Length of the arrow head.", this, &PathDisplay::updatePoseArrowGeometry);
101  new rviz::FloatProperty("Shaft Diameter", 0.1, "Diameter of the arrow shaft.", this,
104  "Head Diameter", 0.3, "Diameter of the arrow head.", this, &PathDisplay::updatePoseArrowGeometry);
112 }
113 
115 {
116  destroyObjects();
119 }
120 
122 {
125 }
126 
128 {
129  MFDClass::reset();
131 }
132 
133 
134 void PathDisplay::allocateAxesVector(std::vector<rviz::Axes*>& axes_vect, size_t num)
135 {
136  if (num > axes_vect.size())
137  {
138  for (size_t i = axes_vect.size(); i < num; ++i)
139  {
140  rviz::Axes* axes =
143  axes_vect.push_back(axes);
144  }
145  }
146  else if (num < axes_vect.size())
147  {
148  for (size_t i = num; i < axes_vect.size(); ++i)
149  {
150  delete axes_vect[i];
151  }
152  axes_vect.resize(num);
153  }
154 }
155 
156 void PathDisplay::allocateArrowVector(std::vector<rviz::Arrow*>& arrow_vect, size_t num)
157 {
158  if (num > arrow_vect.size())
159  {
160  for (size_t i = arrow_vect.size(); i < num; ++i)
161  {
163  arrow_vect.push_back(arrow);
164  }
165  }
166  else if (num < arrow_vect.size())
167  {
168  for (size_t i = num; i < arrow_vect.size(); ++i)
169  {
170  delete arrow_vect[i];
171  }
172  arrow_vect.resize(num);
173  }
174 }
175 
177 {
178  for (size_t i = 0; i < axes_chain_.size(); i++)
179  {
181  }
182  axes_chain_.resize(0);
183 }
184 
186 {
187  for (size_t i = 0; i < arrow_chain_.size(); i++)
188  {
190  }
191  arrow_chain_.resize(0);
192 }
193 
195 {
197 
198  switch (style)
199  {
200  case LINES:
201  default:
203  break;
204 
205  case BILLBOARDS:
207  break;
208  }
209 
211 }
212 
214 {
216  float line_width = line_width_property_->getFloat();
217 
218  if (style == BILLBOARDS)
219  {
220  for (size_t i = 0; i < billboard_lines_.size(); i++)
221  {
222  rviz::BillboardLine* billboard_line = billboard_lines_[i];
223  if (billboard_line)
224  billboard_line->setLineWidth(line_width);
225  }
226  }
228 }
229 
231 {
232  scene_node_->setPosition(offset_property_->getVector());
234 }
235 
237 {
239  switch (pose_style)
240  {
241  case AXES:
249  break;
250  case ARROWS:
258  break;
259  default:
267  }
269 }
270 
272 {
273  for (size_t i = 0; i < axes_chain_.size(); i++)
274  {
275  std::vector<rviz::Axes*>& axes_vect = axes_chain_[i];
276  for (size_t j = 0; j < axes_vect.size(); j++)
277  {
279  }
280  }
282 }
283 
285 {
286  QColor color = pose_arrow_color_property_->getColor();
287 
288  for (size_t i = 0; i < arrow_chain_.size(); i++)
289  {
290  std::vector<rviz::Arrow*>& arrow_vect = arrow_chain_[i];
291  for (size_t j = 0; j < arrow_vect.size(); j++)
292  {
293  arrow_vect[j]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
294  }
295  }
297 }
298 
300 {
301  for (size_t i = 0; i < arrow_chain_.size(); i++)
302  {
303  std::vector<rviz::Arrow*>& arrow_vect = arrow_chain_[i];
304  for (size_t j = 0; j < arrow_vect.size(); j++)
305  {
306  arrow_vect[j]->set(pose_arrow_shaft_length_property_->getFloat(),
310  }
311  }
313 }
314 
316 {
317  // Destroy all simple lines, if any
318  for (size_t i = 0; i < manual_objects_.size(); i++)
319  {
320  Ogre::ManualObject*& manual_object = manual_objects_[i];
321  if (manual_object)
322  {
323  manual_object->clear();
324  scene_manager_->destroyManualObject(manual_object);
325  manual_object = nullptr; // ensure it doesn't get destroyed again
326  }
327  }
328 
329  // Destroy all billboards, if any
330  for (size_t i = 0; i < billboard_lines_.size(); i++)
331  {
332  rviz::BillboardLine*& billboard_line = billboard_lines_[i];
333  if (billboard_line)
334  {
335  delete billboard_line; // also destroys the corresponding scene node
336  billboard_line = nullptr; // ensure it doesn't get destroyed again
337  }
338  }
339 }
340 
342 {
343  // Delete old path objects
344  destroyObjects();
345 
346  // Destroy all axes and arrows
349 
350  // Read options
351  int buffer_length = buffer_length_property_->getInt();
353 
354  // Create new path objects
355  switch (style)
356  {
357  case LINES: // simple lines with fixed width of 1px
358  manual_objects_.resize(buffer_length);
359  for (size_t i = 0; i < manual_objects_.size(); i++)
360  {
361  Ogre::ManualObject* manual_object = scene_manager_->createManualObject();
362  manual_object->setDynamic(true);
363  scene_node_->attachObject(manual_object);
364 
365  manual_objects_[i] = manual_object;
366  }
367  break;
368 
369  case BILLBOARDS: // billboards with configurable width
370  billboard_lines_.resize(buffer_length);
371  for (size_t i = 0; i < billboard_lines_.size(); i++)
372  {
374  billboard_lines_[i] = billboard_line;
375  }
376  break;
377  }
378  axes_chain_.resize(buffer_length);
379  arrow_chain_.resize(buffer_length);
380 }
381 
382 bool validateFloats(const nav_msgs::Path& msg)
383 {
384  bool valid = true;
385  valid = valid && validateFloats(msg.poses);
386  return valid;
387 }
388 
389 void PathDisplay::processMessage(const nav_msgs::Path::ConstPtr& msg)
390 {
391  // Calculate index of oldest element in cyclic buffer
392  size_t bufferIndex = messages_received_ % buffer_length_property_->getInt();
393 
395  Ogre::ManualObject* manual_object = nullptr;
396  rviz::BillboardLine* billboard_line = nullptr;
397 
398  // Delete oldest element
399  switch (style)
400  {
401  case LINES:
402  manual_object = manual_objects_[bufferIndex];
403  manual_object->clear();
404  break;
405 
406  case BILLBOARDS:
407  billboard_line = billboard_lines_[bufferIndex];
408  billboard_line->clear();
409  break;
410  }
411 
412  // Check if path contains invalid coordinate values
413  if (!validateFloats(*msg))
414  {
416  "Message contained invalid floating point values (nans or infs)");
417  return;
418  }
419 
420  if (!validateQuaternions(msg->poses))
421  {
422  ROS_WARN_ONCE_NAMED("quaternions",
423  "Path '%s' contains unnormalized quaternions. "
424  "This warning will only be output once but may be true for others; "
425  "enable DEBUG messages for ros.rviz.quaternions to see more details.",
426  qPrintable(getName()));
427  ROS_DEBUG_NAMED("quaternions", "Path '%s' contains unnormalized quaternions.", qPrintable(getName()));
428  }
429 
430  // Lookup transform into fixed frame
431  Ogre::Vector3 position;
432  Ogre::Quaternion orientation;
433  if (!context_->getFrameManager()->getTransform(msg->header, position, orientation))
434  {
435  ROS_DEBUG("Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(),
436  qPrintable(fixed_frame_));
437  }
438 
439  Ogre::Matrix4 transform(orientation);
440  transform.setTrans(position);
441 
442  // scene_node_->setPosition( position );
443  // scene_node_->setOrientation( orientation );
444 
445  Ogre::ColourValue color = color_property_->getOgreColor();
446  color.a = alpha_property_->getFloat();
447 
448  uint32_t num_points = msg->poses.size();
449  float line_width = line_width_property_->getFloat();
450 
451  switch (style)
452  {
453  case LINES:
454  manual_object->estimateVertexCount(num_points);
455  manual_object->begin("BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP,
456  Ogre::ResourceGroupManager::INTERNAL_RESOURCE_GROUP_NAME);
457  for (uint32_t i = 0; i < num_points; ++i)
458  {
459  const geometry_msgs::Point& pos = msg->poses[i].pose.position;
460  Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
461  manual_object->position(xpos.x, xpos.y, xpos.z);
462  manual_object->colour(color);
463  }
464 
465  manual_object->end();
466  break;
467 
468  case BILLBOARDS:
469  billboard_line->setNumLines(1);
470  billboard_line->setMaxPointsPerLine(num_points);
471  billboard_line->setLineWidth(line_width);
472 
473  for (uint32_t i = 0; i < num_points; ++i)
474  {
475  const geometry_msgs::Point& pos = msg->poses[i].pose.position;
476  Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
477  billboard_line->addPoint(xpos, color);
478  }
479 
480  break;
481  }
482 
483  // process pose markers
485  std::vector<rviz::Arrow*>& arrow_vect = arrow_chain_[bufferIndex];
486  std::vector<rviz::Axes*>& axes_vect = axes_chain_[bufferIndex];
487 
488  switch (pose_style)
489  {
490  case AXES:
491  allocateAxesVector(axes_vect, num_points);
492  for (uint32_t i = 0; i < num_points; ++i)
493  {
494  const geometry_msgs::Point& pos = msg->poses[i].pose.position;
495  const geometry_msgs::Quaternion& quat = msg->poses[i].pose.orientation;
496  Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
497  Ogre::Quaternion xquat = orientation * Ogre::Quaternion(quat.w, quat.x, quat.y, quat.z);
498  axes_vect[i]->setPosition(xpos);
499  axes_vect[i]->setOrientation(xquat);
500  }
501  break;
502 
503  case ARROWS:
504  allocateArrowVector(arrow_vect, num_points);
505  for (uint32_t i = 0; i < num_points; ++i)
506  {
507  const geometry_msgs::Point& pos = msg->poses[i].pose.position;
508  const geometry_msgs::Quaternion& quat = msg->poses[i].pose.orientation;
509  Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
510  Ogre::Quaternion xquat = orientation * Ogre::Quaternion(quat.w, quat.x, quat.y, quat.z);
511 
512  QColor color = pose_arrow_color_property_->getColor();
513  arrow_vect[i]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
514 
515  arrow_vect[i]->set(pose_arrow_shaft_length_property_->getFloat(),
519  arrow_vect[i]->setPosition(xpos);
520  arrow_vect[i]->setDirection(xquat * Ogre::Vector3(1, 0, 0));
521  }
522  break;
523 
524  default:
525  break;
526  }
528 }
529 
530 } // namespace rviz
531 
rviz::BillboardLine::clear
void clear()
Definition: billboard_line.cpp:105
rviz::BillboardLine
An object that displays a multi-segment line strip rendered as billboards.
Definition: billboard_line.h:58
rviz::EnumProperty::getOptionInt
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
Definition: enum_property.cpp:56
rviz::IntProperty::setMin
void setMin(int min)
Definition: int_property.cpp:52
rviz::PathDisplay
Displays a nav_msgs::Path message.
Definition: path_display.h:59
rviz::BillboardLine::setLineWidth
void setLineWidth(float width)
Definition: billboard_line.cpp:237
rviz::PathDisplay::alpha_property_
FloatProperty * alpha_property_
Definition: path_display.h:100
rviz::ColorProperty::getColor
virtual QColor getColor() const
Definition: color_property.h:79
rviz::MessageFilterDisplay< nav_msgs::Path >::reset
void reset() override
Definition: message_filter_display.h:125
validate_floats.h
frame_manager.h
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
rviz::PathDisplay::destroyObjects
void destroyObjects()
Definition: path_display.cpp:315
rviz::PathDisplay::offset_property_
VectorProperty * offset_property_
Definition: path_display.h:103
rviz::PathDisplay::reset
void reset() override
Overridden from Display.
Definition: path_display.cpp:127
rviz::Arrow
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:57
rviz::StatusProperty::Error
@ Error
Definition: status_property.h:46
rviz::PathDisplay::style_property_
EnumProperty * style_property_
Definition: path_display.h:98
rviz::PathDisplay::pose_style_property_
EnumProperty * pose_style_property_
Definition: path_display.h:112
rviz::PathDisplay::line_width_property_
FloatProperty * line_width_property_
Definition: path_display.h:101
rviz::PathDisplay::destroyPoseArrowChain
void destroyPoseArrowChain()
Definition: path_display.cpp:185
rviz::PathDisplay::PathDisplay
PathDisplay()
Definition: path_display.cpp:52
rviz::Property::show
void show()
Show this Property in any PropertyTreeWidgets.
Definition: property.h:471
rviz::PathDisplay::AXES
@ AXES
Definition: path_display.h:124
rviz::PathDisplay::LineStyle
LineStyle
Definition: path_display.h:105
rviz::PathDisplay::NONE
@ NONE
Definition: path_display.h:123
int_property.h
rviz::PathDisplay::destroyPoseAxesChain
void destroyPoseAxesChain()
Definition: path_display.cpp:176
rviz::validateFloats
bool validateFloats(const sensor_msgs::CameraInfo &msg)
Definition: camera_display.cpp:72
rviz::PathDisplay::updateStyle
void updateStyle()
Definition: path_display.cpp:194
rviz::PathDisplay::BILLBOARDS
@ BILLBOARDS
Definition: path_display.h:108
rviz::PathDisplay::updatePoseArrowGeometry
void updatePoseArrowGeometry()
Definition: path_display.cpp:299
float_property.h
ROS_WARN_ONCE_NAMED
#define ROS_WARN_ONCE_NAMED(name,...)
rviz::PathDisplay::~PathDisplay
~PathDisplay() override
Definition: path_display.cpp:114
rviz::Display::fixed_frame_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
path_display.h
validate_quaternions.h
rviz::BillboardLine::setMaxPointsPerLine
void setMaxPointsPerLine(uint32_t max)
Definition: billboard_line.cpp:169
rviz::FloatProperty::setMin
void setMin(float min)
Definition: float_property.cpp:51
rviz::ColorProperty
Definition: color_property.h:40
rviz::PathDisplay::pose_arrow_head_length_property_
FloatProperty * pose_arrow_head_length_property_
Definition: path_display.h:117
rviz::Display
Definition: display.h:63
rviz::EnumProperty
Enum property.
Definition: enum_property.h:46
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::PathDisplay::updatePoseAxisGeometry
void updatePoseAxisGeometry()
Definition: path_display.cpp:271
rviz::PathDisplay::color_property_
ColorProperty * color_property_
Definition: path_display.h:99
rviz::Property::hide
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:462
rviz::Display::setStatus
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:176
rviz::PathDisplay::updatePoseStyle
void updatePoseStyle()
Definition: path_display.cpp:236
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::FloatProperty::getFloat
virtual float getFloat() const
Definition: float_property.h:79
rviz::EnumProperty::addOption
virtual void addOption(const QString &option, int value=0)
Definition: enum_property.cpp:50
ROS_DEBUG
#define ROS_DEBUG(...)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
rviz::PathDisplay::pose_arrow_color_property_
ColorProperty * pose_arrow_color_property_
Definition: path_display.h:115
rviz
Definition: add_display_dialog.cpp:54
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
color_property.h
rviz::validateQuaternions
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
Definition: interactive_marker_display.cpp:63
rviz::Display::scene_manager_
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
Definition: display.h:292
rviz::PathDisplay::allocateArrowVector
void allocateArrowVector(std::vector< rviz::Arrow * > &arrow_vect, size_t num)
Definition: path_display.cpp:156
rviz::BillboardLine::setNumLines
void setNumLines(uint32_t num)
Definition: billboard_line.cpp:187
rviz::PathDisplay::pose_arrow_head_diameter_property_
FloatProperty * pose_arrow_head_diameter_property_
Definition: path_display.h:119
rviz::PathDisplay::LINES
@ LINES
Definition: path_display.h:107
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
rviz::MessageFilterDisplay< nav_msgs::Path >::messages_received_
uint32_t messages_received_
Definition: message_filter_display.h:233
rviz::PathDisplay::updateLineWidth
void updateLineWidth()
Definition: path_display.cpp:213
rviz::PathDisplay::updateOffset
void updateOffset()
Definition: path_display.cpp:230
rviz::Axes
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Definition: axes.h:57
billboard_line.h
rviz::MessageFilterDisplay< nav_msgs::Path >::onInitialize
void onInitialize() override
Definition: message_filter_display.h:105
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
Definition: frame_manager.h:125
rviz::PathDisplay::PoseStyle
PoseStyle
Definition: path_display.h:121
rviz::PathDisplay::ARROWS
@ ARROWS
Definition: path_display.h:125
rviz::Property::getName
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:164
rviz::PathDisplay::processMessage
void processMessage(const nav_msgs::Path::ConstPtr &msg) override
Overridden from MessageFilterDisplay.
Definition: path_display.cpp:389
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Definition: display.h:287
vector_property.h
rviz::PathDisplay::onInitialize
void onInitialize() override
Overridden from Display.
Definition: path_display.cpp:121
rviz::PathDisplay::pose_axes_length_property_
FloatProperty * pose_axes_length_property_
Definition: path_display.h:113
rviz::PathDisplay::billboard_lines_
std::vector< rviz::BillboardLine * > billboard_lines_
Definition: path_display.h:94
rviz::PathDisplay::pose_arrow_shaft_diameter_property_
FloatProperty * pose_arrow_shaft_diameter_property_
Definition: path_display.h:118
class_list_macros.hpp
rviz::IntProperty::getInt
virtual int getInt() const
Return the internal property value as an integer.
Definition: int_property.h:96
rviz::PathDisplay::pose_arrow_shaft_length_property_
FloatProperty * pose_arrow_shaft_length_property_
Definition: path_display.h:116
rviz::PathDisplay::updateBufferLength
void updateBufferLength()
Definition: path_display.cpp:341
display_context.h
rviz::VectorProperty
Definition: vector_property.h:39
rviz::PathDisplay::arrow_chain_
std::vector< std::vector< rviz::Arrow * > > arrow_chain_
Definition: path_display.h:96
rviz::PathDisplay::allocateAxesVector
void allocateAxesVector(std::vector< rviz::Axes * > &axes_vect, size_t num)
Definition: path_display.cpp:134
rviz::PathDisplay::manual_objects_
std::vector< Ogre::ManualObject * > manual_objects_
Definition: path_display.h:93
rviz::PathDisplay::pose_axes_radius_property_
FloatProperty * pose_axes_radius_property_
Definition: path_display.h:114
rviz::PathDisplay::updatePoseArrowColor
void updatePoseArrowColor()
Definition: path_display.cpp:284
rviz::VectorProperty::getVector
virtual Ogre::Vector3 getVector() const
Definition: vector_property.h:73
rviz::PathDisplay::axes_chain_
std::vector< std::vector< rviz::Axes * > > axes_chain_
Definition: path_display.h:95
rviz::PathDisplay::buffer_length_property_
IntProperty * buffer_length_property_
Definition: path_display.h:102
rviz::ColorProperty::getOgreColor
Ogre::ColourValue getOgreColor() const
Definition: color_property.h:83
enum_property.h
rviz::BillboardLine::addPoint
void addPoint(const Ogre::Vector3 &point)
Definition: billboard_line.cpp:208
rviz::IntProperty
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:37


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Dec 13 2024 03:31:02