pose_with_covariance_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, Ellon Paiva Mendes @ LAAS-CNRS
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 <OgreEntity.h>
31 #include <OgreSceneNode.h>
32 
33 #include <rviz/display_context.h>
34 #include <rviz/frame_manager.h>
36 #include <rviz/ogre_helpers/axes.h>
46 #include <rviz/validate_floats.h>
48 
50 #include "covariance_visual.h"
51 #include "covariance_property.h"
52 
53 #include <Eigen/Dense>
54 
55 namespace rviz
56 {
58 {
59 public:
61  : SelectionHandler(context), display_(display)
62  {
63  }
64 
65  void createProperties(const Picked& /*obj*/, Property* parent_property) override
66  {
67  Property* cat = new Property("Pose " + display_->getName(), QVariant(), "", parent_property);
68  properties_.push_back(cat);
69 
70  frame_property_ = new StringProperty("Frame", "", "", cat);
72 
73  position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, "", cat);
75 
76  orientation_property_ = new QuaternionProperty("Orientation", Ogre::Quaternion::IDENTITY, "", cat);
78 
80  new VectorProperty("Covariance Position", Ogre::Vector3::ZERO, "", cat);
82 
84  new VectorProperty("Covariance Orientation", Ogre::Vector3::ZERO, "", cat);
86  }
87 
88  void getAABBs(const Picked& /*obj*/, V_AABB& aabbs) override
89  {
90  if (display_->pose_valid_)
91  {
93  {
94  aabbs.push_back(display_->arrow_->getHead()->getEntity()->getWorldBoundingBox());
95  aabbs.push_back(display_->arrow_->getShaft()->getEntity()->getWorldBoundingBox());
96  }
97  else
98  {
99  aabbs.push_back(display_->axes_->getXShape()->getEntity()->getWorldBoundingBox());
100  aabbs.push_back(display_->axes_->getYShape()->getEntity()->getWorldBoundingBox());
101  aabbs.push_back(display_->axes_->getZShape()->getEntity()->getWorldBoundingBox());
102  }
103 
105  {
107  {
108  aabbs.push_back(display_->covariance_->getPositionShape()->getEntity()->getWorldBoundingBox());
109  }
111  {
112  aabbs.push_back(display_->covariance_->getOrientationShape(CovarianceVisual::kRoll)
113  ->getEntity()
114  ->getWorldBoundingBox());
115  aabbs.push_back(display_->covariance_->getOrientationShape(CovarianceVisual::kPitch)
116  ->getEntity()
117  ->getWorldBoundingBox());
118  aabbs.push_back(display_->covariance_->getOrientationShape(CovarianceVisual::kYaw)
119  ->getEntity()
120  ->getWorldBoundingBox());
121  }
122  }
123  }
124  }
125 
126  void setMessage(const geometry_msgs::PoseWithCovarianceStampedConstPtr& message)
127  {
128  // properties_.size() should only be > 0 after createProperties()
129  // and before destroyProperties(), during which frame_property_,
130  // position_property_, and orientation_property_ should be valid
131  // pointers.
132  if (!properties_.empty())
133  {
134  frame_property_->setStdString(message->header.frame_id);
135  position_property_->setVector(Ogre::Vector3(
136  message->pose.pose.position.x, message->pose.pose.position.y, message->pose.pose.position.z));
138  Ogre::Quaternion(message->pose.pose.orientation.w, message->pose.pose.orientation.x,
139  message->pose.pose.orientation.y, message->pose.pose.orientation.z));
140  covariance_position_property_->setVector(Ogre::Vector3(message->pose.covariance[0 + 0 * 6],
141  message->pose.covariance[1 + 1 * 6],
142  message->pose.covariance[2 + 2 * 6]));
143 
144  covariance_orientation_property_->setVector(Ogre::Vector3(message->pose.covariance[3 + 3 * 6],
145  message->pose.covariance[4 + 4 * 6],
146  message->pose.covariance[5 + 5 * 6]));
147  }
148  }
149 
150 private:
157 };
158 
160 {
161  shape_property_ = new EnumProperty("Shape", "Arrow", "Shape to display the pose as.", this,
163  shape_property_->addOption("Arrow", Arrow);
164  shape_property_->addOption("Axes", Axes);
165 
166  color_property_ = new ColorProperty("Color", QColor(255, 25, 0), "Color to draw the arrow.", this,
168 
169  alpha_property_ = new FloatProperty("Alpha", 1, "Amount of transparency to apply to the arrow.", this,
173 
175  new FloatProperty("Shaft Length", 1, "Length of the arrow's shaft, in meters.", this,
177 
178  // aleeper: default changed from 0.1 to match change in arrow.cpp
180  new FloatProperty("Shaft Radius", 0.05, "Radius of the arrow's shaft, in meters.", this,
182 
183  head_length_property_ = new FloatProperty("Head Length", 0.3, "Length of the arrow's head, in meters.",
185 
186  // aleeper: default changed from 0.2 to match change in arrow.cpp
187  head_radius_property_ = new FloatProperty("Head Radius", 0.1, "Radius of the arrow's head, in meters.",
189 
190  axes_length_property_ = new FloatProperty("Axes Length", 1, "Length of each axis, in meters.", this,
192 
193  axes_radius_property_ = new FloatProperty("Axes Radius", 0.1, "Radius of each axis, in meters.", this,
195 
197  new CovarianceProperty("Covariance", true,
198  "Whether or not the covariances of the messages should be shown.", this,
200 }
201 
203 {
205 
209  // Arrow points in -Z direction, so rotate the orientation before display.
210  // TODO: is it safe to change Arrow to point in +X direction?
211  arrow_->setOrientation(Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y));
212 
215 
217 
220 
222  coll_handler_->addTrackedObjects(arrow_->getSceneNode());
223  coll_handler_->addTrackedObjects(axes_->getSceneNode());
224  coll_handler_->addTrackedObjects(covariance_->getPositionSceneNode());
225  coll_handler_->addTrackedObjects(covariance_->getOrientationSceneNode());
226 }
227 
229 {
230  if (initialized())
231  {
232  delete arrow_;
233  delete axes_;
234  }
235 }
236 
238 {
241 }
242 
244 {
245  Ogre::ColourValue color = color_property_->getOgreColor();
246  color.a = alpha_property_->getFloat();
247 
248  arrow_->setColor(color);
249 
251 }
252 
254 {
258 }
259 
261 {
264 }
265 
267 {
268  bool use_arrow = (shape_property_->getOptionInt() == Arrow);
269 
270  color_property_->setHidden(!use_arrow);
271  alpha_property_->setHidden(!use_arrow);
272  shaft_length_property_->setHidden(!use_arrow);
273  shaft_radius_property_->setHidden(!use_arrow);
274  head_length_property_->setHidden(!use_arrow);
275  head_radius_property_->setHidden(!use_arrow);
276 
277  axes_length_property_->setHidden(use_arrow);
278  axes_radius_property_->setHidden(use_arrow);
279 
281 
283 }
284 
286 {
287  if (!pose_valid_)
288  {
289  arrow_->getSceneNode()->setVisible(false);
290  axes_->getSceneNode()->setVisible(false);
291  covariance_->setVisible(false);
292  }
293  else
294  {
295  bool use_arrow = (shape_property_->getOptionInt() == Arrow);
296  arrow_->getSceneNode()->setVisible(use_arrow);
297  axes_->getSceneNode()->setVisible(!use_arrow);
299  }
300 }
301 
303  const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& message)
304 {
305  if (!validateFloats(message->pose.pose) || !validateFloats(message->pose.covariance))
306  {
308  "Message contained invalid floating point values (nans or infs)");
309  return;
310  }
311 
312  if (!validateQuaternions(message->pose.pose))
313  {
314  ROS_WARN_ONCE_NAMED("quaternions",
315  "PoseWithCovariance '%s' contains unnormalized quaternions. "
316  "This warning will only be output once but may be true for others; "
317  "enable DEBUG messages for ros.rviz.quaternions to see more details.",
318  qPrintable(getName()));
319  ROS_DEBUG_NAMED("quaternions", "PoseWithCovariance '%s' contains unnormalized quaternions.",
320  qPrintable(getName()));
321  }
322 
323  Ogre::Vector3 position;
324  Ogre::Quaternion orientation;
325  if (!context_->getFrameManager()->transform(message->header, message->pose.pose, position, orientation))
326  {
327  ROS_ERROR("Error transforming pose '%s' from frame '%s' to frame '%s'", qPrintable(getName()),
328  message->header.frame_id.c_str(), qPrintable(fixed_frame_));
329  return;
330  }
331 
332  pose_valid_ = true;
334 
335  axes_->setPosition(position);
336  axes_->setOrientation(orientation);
337 
338  arrow_->setPosition(position);
339  arrow_->setOrientation(orientation * Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y));
340 
341  covariance_->setPosition(position);
342  covariance_->setOrientation(orientation);
343  covariance_->setCovariance(message->pose);
344 
345  coll_handler_->setMessage(message);
346 
348 }
349 
351 {
352  MFDClass::reset();
353  pose_valid_ = false;
355 }
356 
357 } // namespace rviz
358 
rviz::Arrow::set
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
Definition: arrow.cpp:74
shape.h
rviz::BoolProperty::getBool
virtual bool getBool() const
Definition: bool_property.cpp:48
axes.h
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::Axes::getSceneNode
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
Definition: axes.h:96
rviz::PoseWithCovarianceDisplay::updateColorAndAlpha
void updateColorAndAlpha()
Definition: pose_with_covariance_display.cpp:243
rviz::PoseWithCovarianceDisplay::onInitialize
void onInitialize() override
Override this function to do subclass-specific initialization.
Definition: pose_with_covariance_display.cpp:202
rviz::PoseWithCovarianceDisplay::updateAxisGeometry
void updateAxisGeometry()
Definition: pose_with_covariance_display.cpp:260
rviz::MessageFilterDisplay< geometry_msgs::PoseWithCovarianceStamped >::reset
void reset() override
Definition: message_filter_display.h:125
validate_floats.h
frame_manager.h
rviz::Property::setHidden
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
Definition: property.cpp:566
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
rviz::PoseWithCovarianceDisplay::Arrow
@ Arrow
Definition: pose_with_covariance_display.h:65
rviz::PoseWithCovarianceDisplaySelectionHandler::PoseWithCovarianceDisplaySelectionHandler
PoseWithCovarianceDisplaySelectionHandler(PoseWithCovarianceDisplay *display, DisplayContext *context)
Definition: pose_with_covariance_display.cpp:60
rviz::Display::queueRender
void queueRender()
Convenience function which calls context_->queueRender().
Definition: display.cpp:99
rviz::Arrow
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:57
rviz::Display::initialized
bool initialized() const
Returns true if the display has been initialized.
Definition: display.h:275
rviz::StatusProperty::Error
@ Error
Definition: status_property.h:46
rviz::PoseWithCovarianceDisplaySelectionHandler::getAABBs
void getAABBs(const Picked &, V_AABB &aabbs) override
Definition: pose_with_covariance_display.cpp:88
rviz::Arrow::setOrientation
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
Definition: arrow.cpp:119
rviz::PoseWithCovarianceDisplay::head_length_property_
rviz::FloatProperty * head_length_property_
Definition: pose_with_covariance_display.h:103
rviz::CovarianceProperty::createAndPushBackVisual
CovarianceVisualPtr createAndPushBackVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
Definition: covariance_property.cpp:226
rviz::PoseWithCovarianceDisplay::covariance_
boost::shared_ptr< CovarianceVisual > covariance_
Definition: pose_with_covariance_display.h:93
rviz::Axes::getYShape
Shape * getYShape()
Definition: axes.h:110
rviz::PoseWithCovarianceDisplaySelectionHandler
Definition: pose_with_covariance_display.cpp:57
rviz::PoseWithCovarianceDisplaySelectionHandler::position_property_
VectorProperty * position_property_
Definition: pose_with_covariance_display.cpp:153
rviz::FloatProperty::setMax
void setMax(float max)
Definition: float_property.cpp:57
rviz::CovarianceProperty::getPositionBool
bool getPositionBool()
Definition: covariance_property.cpp:238
rviz::CovarianceProperty::updateVisibility
void updateVisibility()
Definition: covariance_property.cpp:171
rviz::CovarianceProperty
Property specialized to provide getter for booleans.
Definition: covariance_property.h:56
rviz::validateFloats
bool validateFloats(const sensor_msgs::CameraInfo &msg)
Definition: camera_display.cpp:72
rviz::PoseWithCovarianceDisplay::shape_property_
rviz::EnumProperty * shape_property_
Definition: pose_with_covariance_display.h:97
rviz::PoseWithCovarianceDisplay::axes_radius_property_
rviz::FloatProperty * axes_radius_property_
Definition: pose_with_covariance_display.h:108
float_property.h
ROS_WARN_ONCE_NAMED
#define ROS_WARN_ONCE_NAMED(name,...)
rviz::PoseWithCovarianceDisplay::updateShapeChoice
void updateShapeChoice()
Definition: pose_with_covariance_display.cpp:266
rviz::PoseWithCovarianceDisplay::PoseWithCovarianceDisplaySelectionHandler
friend class PoseWithCovarianceDisplaySelectionHandler
Definition: pose_with_covariance_display.h:112
selection_manager.h
rviz::CovarianceProperty::getOrientationBool
bool getOrientationBool()
Definition: covariance_property.cpp:243
rviz::Display::fixed_frame_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
rviz::PoseWithCovarianceDisplaySelectionHandler::setMessage
void setMessage(const geometry_msgs::PoseWithCovarianceStampedConstPtr &message)
Definition: pose_with_covariance_display.cpp:126
rviz::CovarianceVisual::kYaw
@ kYaw
Definition: covariance_visual.h:75
validate_quaternions.h
rviz::QuaternionProperty::setReadOnly
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
Definition: quaternion_property.cpp:158
bool_property.h
rviz::PoseWithCovarianceDisplaySelectionHandler::orientation_property_
QuaternionProperty * orientation_property_
Definition: pose_with_covariance_display.cpp:154
rviz::Arrow::getShaft
Shape * getShaft()
Definition: arrow.h:157
rviz::PoseWithCovarianceDisplaySelectionHandler::covariance_orientation_property_
VectorProperty * covariance_orientation_property_
Definition: pose_with_covariance_display.cpp:156
rviz::PoseWithCovarianceDisplay::~PoseWithCovarianceDisplay
~PoseWithCovarianceDisplay() override
Definition: pose_with_covariance_display.cpp:228
rviz::FloatProperty::setMin
void setMin(float min)
Definition: float_property.cpp:51
rviz::MessageFilterDisplay< geometry_msgs::PoseWithCovarianceStamped >::onEnable
void onEnable() override
Definition: message_filter_display.h:182
rviz::ColorProperty
Definition: color_property.h:40
quaternion_property.h
rviz::Display
Definition: display.h:63
rviz::EnumProperty
Enum property.
Definition: enum_property.h:46
rviz::PoseWithCovarianceDisplay::coll_handler_
PoseWithCovarianceDisplaySelectionHandlerPtr coll_handler_
Definition: pose_with_covariance_display.h:95
rviz::QuaternionProperty
Definition: quaternion_property.h:38
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::Picked
Definition: forwards.h:53
rviz::Property
A single element of a property tree, with a name, value, description, and possibly children.
Definition: property.h:100
rviz::PoseWithCovarianceDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: pose_with_covariance_display.cpp:350
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::PoseWithCovarianceDisplay::updateArrowGeometry
void updateArrowGeometry()
Definition: pose_with_covariance_display.cpp:253
covariance_property.h
rviz::Axes::getXShape
Shape * getXShape()
Definition: axes.h:106
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_NAMED
#define ROS_DEBUG_NAMED(name,...)
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
rviz::VectorProperty::setVector
virtual bool setVector(const Ogre::Vector3 &vector)
Definition: vector_property.cpp:55
rviz::Arrow::getHead
Shape * getHead()
Definition: arrow.h:161
rviz::QuaternionProperty::setQuaternion
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
Definition: quaternion_property.cpp:60
color_property.h
rviz::StringProperty
Property specialized for string values.
Definition: string_property.h:39
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
arrow.h
rviz::PoseWithCovarianceDisplay::processMessage
void processMessage(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &message) override
Definition: pose_with_covariance_display.cpp:302
rviz::PoseWithCovarianceDisplay::shaft_radius_property_
rviz::FloatProperty * shaft_radius_property_
Definition: pose_with_covariance_display.h:104
rviz::Shape::getEntity
Ogre::Entity * getEntity()
Definition: shape.h:110
pose_with_covariance_display.h
rviz::DisplayContext
Pure-virtual base class for objects which give Display subclasses context in which to work.
Definition: display_context.h:81
rviz::PoseWithCovarianceDisplay::head_radius_property_
rviz::FloatProperty * head_radius_property_
Definition: pose_with_covariance_display.h:102
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
string_property.h
rviz::Axes
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Definition: axes.h:57
rviz::PoseWithCovarianceDisplaySelectionHandler::covariance_position_property_
VectorProperty * covariance_position_property_
Definition: pose_with_covariance_display.cpp:155
rviz::MessageFilterDisplay< geometry_msgs::PoseWithCovarianceStamped >::onInitialize
void onInitialize() override
Definition: message_filter_display.h:105
rviz::V_AABB
std::vector< Ogre::AxisAlignedBox > V_AABB
Definition: selection_handler.h:60
rviz::Property::getName
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:164
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Definition: display.h:287
rviz::Property::setReadOnly
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
Definition: property.h:497
vector_property.h
rviz::PoseWithCovarianceDisplay::covariance_property_
CovarianceProperty * covariance_property_
Definition: pose_with_covariance_display.h:110
rviz::SelectionHandler
Definition: selection_handler.h:64
covariance_visual.h
rviz::PoseWithCovarianceDisplay::axes_
rviz::Axes * axes_
Definition: pose_with_covariance_display.h:92
rviz::VectorProperty::setReadOnly
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
Definition: vector_property.cpp:143
rviz::SelectionHandler::properties_
QList< Property * > properties_
Definition: selection_handler.h:149
ROS_ERROR
#define ROS_ERROR(...)
rviz::StringProperty::setStdString
bool setStdString(const std::string &std_str)
Definition: string_property.h:85
rviz::PoseWithCovarianceDisplay::alpha_property_
rviz::FloatProperty * alpha_property_
Definition: pose_with_covariance_display.h:100
class_list_macros.hpp
rviz::FrameManager::transform
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Transform a pose from a frame into the fixed frame.
Definition: frame_manager.h:148
rviz::CovarianceVisual::kPitch
@ kPitch
Definition: covariance_visual.h:74
rviz::Axes::set
void set(float length, float radius, float alpha=1.0f)
Set the parameters on this object.
Definition: axes.cpp:76
rviz::PoseWithCovarianceDisplay::color_property_
rviz::ColorProperty * color_property_
Definition: pose_with_covariance_display.h:99
rviz::PoseWithCovarianceDisplay::onEnable
void onEnable() override
Overridden from MessageFilterDisplay to get Arrow/Axes visibility correct.
Definition: pose_with_covariance_display.cpp:237
rviz::Axes::getZShape
Shape * getZShape()
Definition: axes.h:114
rviz::PoseWithCovarianceDisplaySelectionHandler::display_
PoseWithCovarianceDisplay * display_
Definition: pose_with_covariance_display.cpp:151
rviz::Axes::setPosition
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
Definition: axes.cpp:92
display_context.h
rviz::VectorProperty
Definition: vector_property.h:39
rviz::Arrow::setPosition
void setPosition(const Ogre::Vector3 &position) override
Set the position of the base of the arrow.
Definition: arrow.cpp:114
rviz::Axes::setOrientation
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
Definition: axes.cpp:97
rviz::Arrow::getSceneNode
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
Definition: arrow.h:147
rviz::Arrow::setColor
void setColor(float r, float g, float b, float a) override
Set the color of this arrow. Sets both the head and shaft color to the same value....
Definition: arrow.cpp:89
rviz::PoseWithCovarianceDisplay::shaft_length_property_
rviz::FloatProperty * shaft_length_property_
Definition: pose_with_covariance_display.h:105
rviz::CovarianceVisual::kRoll
@ kRoll
Definition: covariance_visual.h:73
rviz::PoseWithCovarianceDisplay::updateShapeVisibility
void updateShapeVisibility()
Definition: pose_with_covariance_display.cpp:285
rviz::PoseWithCovarianceDisplay::pose_valid_
bool pose_valid_
Definition: pose_with_covariance_display.h:94
rviz::PoseWithCovarianceDisplay::arrow_
rviz::Arrow * arrow_
Definition: pose_with_covariance_display.h:91
rviz::PoseWithCovarianceDisplaySelectionHandler::frame_property_
StringProperty * frame_property_
Definition: pose_with_covariance_display.cpp:152
rviz::PoseWithCovarianceDisplay::axes_length_property_
rviz::FloatProperty * axes_length_property_
Definition: pose_with_covariance_display.h:107
rviz::PoseWithCovarianceDisplaySelectionHandler::createProperties
void createProperties(const Picked &, Property *parent_property) override
Override to create properties of the given picked object(s).
Definition: pose_with_covariance_display.cpp:65
rviz::PoseWithCovarianceDisplay::PoseWithCovarianceDisplay
PoseWithCovarianceDisplay()
Definition: pose_with_covariance_display.cpp:159
rviz::ColorProperty::getOgreColor
Ogre::ColourValue getOgreColor() const
Definition: color_property.h:83
enum_property.h
rviz::PoseWithCovarianceDisplay
Displays the pose from a geometry_msgs::PoseWithCovarianceStamped message.
Definition: pose_with_covariance_display.h:58


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53