pose_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 <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"
45 #include "rviz/validate_floats.h"
47 
49 
50 namespace rviz
51 {
53 {
54 public:
56  : SelectionHandler(context), display_(display)
57  {
58  }
59 
60  void createProperties(const Picked& /*obj*/, Property* parent_property) override
61  {
62  Property* cat = new Property("Pose " + display_->getName(), QVariant(), "", parent_property);
63  properties_.push_back(cat);
64 
65  frame_property_ = new StringProperty("Frame", "", "", cat);
67 
68  position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, "", cat);
70 
71  orientation_property_ = new QuaternionProperty("Orientation", Ogre::Quaternion::IDENTITY, "", cat);
73  }
74 
75  void getAABBs(const Picked& /*obj*/, V_AABB& aabbs) override
76  {
77  if (display_->pose_valid_)
78  {
80  {
81  aabbs.push_back(display_->arrow_->getHead()->getEntity()->getWorldBoundingBox());
82  aabbs.push_back(display_->arrow_->getShaft()->getEntity()->getWorldBoundingBox());
83  }
84  else
85  {
86  aabbs.push_back(display_->axes_->getXShape()->getEntity()->getWorldBoundingBox());
87  aabbs.push_back(display_->axes_->getYShape()->getEntity()->getWorldBoundingBox());
88  aabbs.push_back(display_->axes_->getZShape()->getEntity()->getWorldBoundingBox());
89  }
90  }
91  }
92 
93  void setMessage(const geometry_msgs::PoseStampedConstPtr& message)
94  {
95  // properties_.size() should only be > 0 after createProperties()
96  // and before destroyProperties(), during which frame_property_,
97  // position_property_, and orientation_property_ should be valid
98  // pointers.
99  if (!properties_.empty())
100  {
101  frame_property_->setStdString(message->header.frame_id);
103  Ogre::Vector3(message->pose.position.x, message->pose.position.y, message->pose.position.z));
105  Ogre::Quaternion(message->pose.orientation.w, message->pose.orientation.x,
106  message->pose.orientation.y, message->pose.orientation.z));
107  }
108  }
109 
110 private:
115 };
116 
117 PoseDisplay::PoseDisplay() : pose_valid_(false)
118 {
119  shape_property_ = new EnumProperty("Shape", "Arrow", "Shape to display the pose as.", this,
120  SLOT(updateShapeChoice()));
121  shape_property_->addOption("Arrow", Arrow);
122  shape_property_->addOption("Axes", Axes);
123 
124  color_property_ = new ColorProperty("Color", QColor(255, 25, 0), "Color to draw the arrow.", this,
125  SLOT(updateColorAndAlpha()));
126 
127  alpha_property_ = new FloatProperty("Alpha", 1, "Amount of transparency to apply to the arrow.", this,
128  SLOT(updateColorAndAlpha()));
131 
133  "Shaft Length", 1, "Length of the arrow's shaft, in meters.", this, SLOT(updateArrowGeometry()));
134 
135  // aleeper: default changed from 0.1 to match change in arrow.cpp
137  new FloatProperty("Shaft Radius", 0.05, "Radius of the arrow's shaft, in meters.", this,
138  SLOT(updateArrowGeometry()));
139 
140  head_length_property_ = new FloatProperty("Head Length", 0.3, "Length of the arrow's head, in meters.",
141  this, SLOT(updateArrowGeometry()));
142 
143  // aleeper: default changed from 0.2 to match change in arrow.cpp
144  head_radius_property_ = new FloatProperty("Head Radius", 0.1, "Radius of the arrow's head, in meters.",
145  this, SLOT(updateArrowGeometry()));
146 
147  axes_length_property_ = new FloatProperty("Axes Length", 1, "Length of each axis, in meters.", this,
148  SLOT(updateAxisGeometry()));
149 
150  axes_radius_property_ = new FloatProperty("Axes Radius", 0.1, "Radius of each axis, in meters.", this,
151  SLOT(updateAxisGeometry()));
152 }
153 
155 {
157 
161  // Arrow points in -Z direction, so rotate the orientation before display.
162  // TODO: is it safe to change Arrow to point in +X direction?
163  arrow_->setOrientation(Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y));
164 
167 
170 
172  coll_handler_->addTrackedObjects(arrow_->getSceneNode());
173  coll_handler_->addTrackedObjects(axes_->getSceneNode());
174 }
175 
177 {
178  if (initialized())
179  {
180  delete arrow_;
181  delete axes_;
182  }
183 }
184 
186 {
189 }
190 
192 {
193  Ogre::ColourValue color = color_property_->getOgreColor();
194  color.a = alpha_property_->getFloat();
195 
196  arrow_->setColor(color);
197 
199 }
200 
202 {
206 }
207 
209 {
212 }
213 
215 {
216  bool use_arrow = (shape_property_->getOptionInt() == Arrow);
217 
218  color_property_->setHidden(!use_arrow);
219  alpha_property_->setHidden(!use_arrow);
220  shaft_length_property_->setHidden(!use_arrow);
221  shaft_radius_property_->setHidden(!use_arrow);
222  head_length_property_->setHidden(!use_arrow);
223  head_radius_property_->setHidden(!use_arrow);
224 
225  axes_length_property_->setHidden(use_arrow);
226  axes_radius_property_->setHidden(use_arrow);
227 
229 
231 }
232 
234 {
235  if (!pose_valid_)
236  {
237  arrow_->getSceneNode()->setVisible(false);
238  axes_->getSceneNode()->setVisible(false);
239  }
240  else
241  {
242  bool use_arrow = (shape_property_->getOptionInt() == Arrow);
243  arrow_->getSceneNode()->setVisible(use_arrow);
244  axes_->getSceneNode()->setVisible(!use_arrow);
245  }
246 }
247 
248 void PoseDisplay::processMessage(const geometry_msgs::PoseStamped::ConstPtr& message)
249 {
250  if (!validateFloats(*message))
251  {
253  "Message contained invalid floating point values (nans or infs)");
254  return;
255  }
256 
257  if (!validateQuaternions(*message))
258  {
259  ROS_WARN_ONCE_NAMED("quaternions",
260  "Pose '%s' contains unnormalized quaternions. "
261  "This warning will only be output once but may be true for others; "
262  "enable DEBUG messages for ros.rviz.quaternions to see more details.",
263  qPrintable(getName()));
264  ROS_DEBUG_NAMED("quaternions", "Pose '%s' contains unnormalized quaternions.", qPrintable(getName()));
265  }
266 
267  Ogre::Vector3 position;
268  Ogre::Quaternion orientation;
269  if (!context_->getFrameManager()->transform(message->header, message->pose, position, orientation))
270  {
271  ROS_ERROR("Error transforming pose '%s' from frame '%s' to frame '%s'", qPrintable(getName()),
272  message->header.frame_id.c_str(), qPrintable(fixed_frame_));
273  return;
274  }
275 
276  pose_valid_ = true;
278 
279  scene_node_->setPosition(position);
280  scene_node_->setOrientation(orientation);
281 
282  coll_handler_->setMessage(message);
283 
285 }
286 
288 {
289  MFDClass::reset();
290  pose_valid_ = false;
292 }
293 
294 } // namespace rviz
295 
Shape * getYShape()
Definition: axes.h:109
void setMin(float min)
FloatProperty * shaft_radius_property_
Definition: pose_display.h:98
void setMax(float max)
void onInitialize() override
Override this function to do subclass-specific initialization.
friend class PoseDisplaySelectionHandler
Definition: pose_display.h:104
virtual bool setVector(const Ogre::Vector3 &vector)
FloatProperty * axes_length_property_
Definition: pose_display.h:101
~PoseDisplay() override
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition: display.h:287
PoseDisplaySelectionHandlerPtr coll_handler_
Definition: pose_display.h:89
A single element of a property tree, with a name, value, description, and possibly children...
Definition: property.h:100
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
Ogre::ColourValue getOgreColor() const
void getAABBs(const Picked &, V_AABB &aabbs) override
Property specialized to enforce floating point max/min.
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
Definition: arrow.cpp:74
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
FloatProperty * shaft_length_property_
Definition: pose_display.h:99
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
Accumulates and displays the pose from a geometry_msgs::PoseStamped message.
Definition: pose_display.h:54
Shape * getHead()
Definition: arrow.h:163
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
Definition: arrow.h:149
void onEnable() override
Overridden from MessageFilterDisplay to get arrow/axes visibility correct.
void setMessage(const geometry_msgs::PoseStampedConstPtr &message)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
#define ROS_DEBUG_NAMED(name,...)
void updateShapeVisibility()
Pure-virtual base class for objects which give Display subclasses context in which to work...
std::vector< Ogre::AxisAlignedBox > V_AABB
bool validateFloats(const sensor_msgs::CameraInfo &msg)
FloatProperty * alpha_property_
Definition: pose_display.h:94
virtual void addOption(const QString &option, int value=0)
QuaternionProperty * orientation_property_
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:164
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
void createProperties(const Picked &, Property *parent_property) override
Override to create properties of the given picked object(s).
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.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
Shape * getXShape()
Definition: axes.h:105
FloatProperty * head_length_property_
Definition: pose_display.h:97
rviz::Axes * axes_
Definition: pose_display.h:87
ColorProperty * color_property_
Definition: pose_display.h:93
#define ROS_WARN_ONCE_NAMED(name,...)
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Definition: axes.h:59
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
Definition: display.h:292
void reset() override
Called to tell the display to clear its state.
EnumProperty * shape_property_
Definition: pose_display.h:91
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
Definition: property.cpp:552
Property specialized for string values.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
void processMessage(const geometry_msgs::PoseStamped::ConstPtr &message) override
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
FloatProperty * axes_radius_property_
Definition: pose_display.h:102
virtual float getFloat() const
QList< Property * > properties_
rviz::Arrow * arrow_
Definition: pose_display.h:86
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:59
void set(float length, float radius)
Set the parameters on this object.
Definition: axes.cpp:68
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
Definition: arrow.cpp:119
Shape * getShaft()
Definition: arrow.h:159
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. Values are in the range [0, 1].
Definition: arrow.cpp:89
bool initialized() const
Returns true if the display has been initialized.
Definition: display.h:275
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
Definition: axes.h:95
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
Definition: property.h:436
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
bool setStdString(const std::string &std_str)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Enum property.
Definition: enum_property.h:46
#define ROS_ERROR(...)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:175
FloatProperty * head_radius_property_
Definition: pose_display.h:96
PoseDisplaySelectionHandler(PoseDisplay *display, DisplayContext *context)
Shape * getZShape()
Definition: axes.h:113
Ogre::Entity * getEntity()
Definition: shape.h:110


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25