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 {
52 
54 {
55 public:
57  : SelectionHandler( context )
58  , display_( display )
59  {}
60 
61  void createProperties( const Picked& obj, Property* parent_property )
62  {
63  Property* cat = new Property( "Pose " + display_->getName(), QVariant(), "", parent_property );
64  properties_.push_back( cat );
65 
66  frame_property_ = new StringProperty( "Frame", "", "", cat );
68 
69  position_property_ = new VectorProperty( "Position", Ogre::Vector3::ZERO, "", cat );
71 
72  orientation_property_ = new QuaternionProperty( "Orientation", Ogre::Quaternion::IDENTITY, "", cat );
74  }
75 
76  void getAABBs( const Picked& obj, V_AABB& aabbs )
77  {
78  if( display_->pose_valid_ )
79  {
81  {
82  aabbs.push_back( display_->arrow_->getHead()->getEntity()->getWorldBoundingBox() );
83  aabbs.push_back( display_->arrow_->getShaft()->getEntity()->getWorldBoundingBox() );
84  }
85  else
86  {
87  aabbs.push_back( display_->axes_->getXShape()->getEntity()->getWorldBoundingBox() );
88  aabbs.push_back( display_->axes_->getYShape()->getEntity()->getWorldBoundingBox() );
89  aabbs.push_back( display_->axes_->getZShape()->getEntity()->getWorldBoundingBox() );
90  }
91  }
92  }
93 
94  void setMessage(const geometry_msgs::PoseStampedConstPtr& message)
95  {
96  // properties_.size() should only be > 0 after createProperties()
97  // and before destroyProperties(), during which frame_property_,
98  // position_property_, and orientation_property_ should be valid
99  // pointers.
100  if( properties_.size() > 0 )
101  {
102  frame_property_->setStdString( message->header.frame_id );
103  position_property_->setVector( Ogre::Vector3( message->pose.position.x,
104  message->pose.position.y,
105  message->pose.position.z ));
106  orientation_property_->setQuaternion( Ogre::Quaternion( message->pose.orientation.w,
107  message->pose.orientation.x,
108  message->pose.orientation.y,
109  message->pose.orientation.z ));
110  }
111  }
112 
113 private:
118 };
119 
121  : pose_valid_( false )
122 {
123  shape_property_ = new EnumProperty( "Shape", "Arrow", "Shape to display the pose as.",
124  this, SLOT( updateShapeChoice() ));
125  shape_property_->addOption( "Arrow", Arrow );
126  shape_property_->addOption( "Axes", Axes );
127 
128  color_property_ = new ColorProperty( "Color", QColor( 255, 25, 0 ), "Color to draw the arrow.",
129  this, SLOT( updateColorAndAlpha() ));
130 
131  alpha_property_ = new FloatProperty( "Alpha", 1, "Amount of transparency to apply to the arrow.",
132  this, SLOT( updateColorAndAlpha() ));
133  alpha_property_->setMin( 0 );
134  alpha_property_->setMax( 1 );
135 
136  shaft_length_property_ = new FloatProperty( "Shaft Length", 1, "Length of the arrow's shaft, in meters.",
137  this, SLOT( updateArrowGeometry() ));
138 
139  // aleeper: default changed from 0.1 to match change in arrow.cpp
140  shaft_radius_property_ = new FloatProperty( "Shaft Radius", 0.05, "Radius of the arrow's shaft, in meters.",
141  this, SLOT( updateArrowGeometry() ));
142 
143  head_length_property_ = new FloatProperty( "Head Length", 0.3, "Length of the arrow's head, in meters.",
144  this, SLOT( updateArrowGeometry() ));
145 
146  // aleeper: default changed from 0.2 to match change in arrow.cpp
147  head_radius_property_ = new FloatProperty( "Head Radius", 0.1, "Radius of the arrow's head, in meters.",
148  this, SLOT( updateArrowGeometry() ));
149 
150  axes_length_property_ = new FloatProperty( "Axes Length", 1, "Length of each axis, in meters.",
151  this, SLOT( updateAxisGeometry() ));
152 
153  axes_radius_property_ = new FloatProperty( "Axes Radius", 0.1, "Radius of each axis, in meters.",
154  this, SLOT( updateAxisGeometry() ));
155 }
156 
158 {
160 
166  // Arrow points in -Z direction, so rotate the orientation before display.
167  // TODO: is it safe to change Arrow to point in +X direction?
168  arrow_->setOrientation( Ogre::Quaternion( Ogre::Degree( -90 ), Ogre::Vector3::UNIT_Y ));
169 
173 
176 
178  coll_handler_->addTrackedObjects( arrow_->getSceneNode() );
179  coll_handler_->addTrackedObjects( axes_->getSceneNode() );
180 }
181 
183 {
184  if ( initialized() )
185  {
186  delete arrow_;
187  delete axes_;
188  }
189 }
190 
192 {
195 }
196 
198 {
199  Ogre::ColourValue color = color_property_->getOgreColor();
200  color.a = alpha_property_->getFloat();
201 
202  arrow_->setColor( color );
203 
205 }
206 
208 {
214 }
215 
217 {
221 }
222 
224 {
225  bool use_arrow = ( shape_property_->getOptionInt() == Arrow );
226 
227  color_property_->setHidden( !use_arrow );
228  alpha_property_->setHidden( !use_arrow );
229  shaft_length_property_->setHidden( !use_arrow );
230  shaft_radius_property_->setHidden( !use_arrow );
231  head_length_property_->setHidden( !use_arrow );
232  head_radius_property_->setHidden( !use_arrow );
233 
234  axes_length_property_->setHidden( use_arrow );
235  axes_radius_property_->setHidden( use_arrow );
236 
238 
240 }
241 
243 {
244  if( !pose_valid_ )
245  {
246  arrow_->getSceneNode()->setVisible( false );
247  axes_->getSceneNode()->setVisible( false );
248  }
249  else
250  {
251  bool use_arrow = (shape_property_->getOptionInt() == Arrow);
252  arrow_->getSceneNode()->setVisible( use_arrow );
253  axes_->getSceneNode()->setVisible( !use_arrow );
254  }
255 }
256 
257 void PoseDisplay::processMessage( const geometry_msgs::PoseStamped::ConstPtr& message )
258 {
259  if( !validateFloats( *message ))
260  {
261  setStatus( StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)" );
262  return;
263  }
264 
265  if( !validateQuaternions( *message ))
266  {
267  ROS_WARN_ONCE_NAMED( "quaternions", "Pose '%s' contains unnormalized quaternions. "
268  "This warning will only be output once but may be true for others; "
269  "enable DEBUG messages for ros.rviz.quaternions to see more details.",
270  qPrintable( getName() ) );
271  ROS_DEBUG_NAMED( "quaternions", "Pose '%s' contains unnormalized quaternions.",
272  qPrintable( getName() ) );
273  }
274 
275  Ogre::Vector3 position;
276  Ogre::Quaternion orientation;
277  if( !context_->getFrameManager()->transform( message->header, message->pose, position, orientation ))
278  {
279  ROS_ERROR( "Error transforming pose '%s' from frame '%s' to frame '%s'",
280  qPrintable( getName() ), message->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
281  return;
282  }
283 
284  pose_valid_ = true;
286 
287  scene_node_->setPosition( position );
288  scene_node_->setOrientation( orientation );
289 
290  coll_handler_->setMessage( message );
291 
293 }
294 
296 {
297  MFDClass::reset();
298  pose_valid_ = false;
300 }
301 
302 } // namespace rviz
303 
Shape * getYShape()
Definition: axes.h:98
void setMin(float min)
FloatProperty * shaft_radius_property_
Definition: pose_display.h:98
void setMax(float max)
Ogre::ColourValue getOgreColor() const
friend class PoseDisplaySelectionHandler
Definition: pose_display.h:104
virtual bool setVector(const Ogre::Vector3 &vector)
FloatProperty * axes_length_property_
Definition: pose_display.h:101
virtual void processMessage(const geometry_msgs::PoseStamped::ConstPtr &message)
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition: display.h:256
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
virtual float getFloat() const
virtual void onEnable()
Overridden from MessageFilterDisplay to get arrow/axes visibility correct.
virtual void setReadOnly(bool read_only)
Overridden from Property to propagate read-only-ness to children.
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:71
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:264
Accumulates and displays the pose from a geometry_msgs::PoseStamped message.
Definition: pose_display.h:54
Shape * getHead()
Definition: arrow.h:151
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
Definition: arrow.h:143
void createProperties(const Picked &obj, Property *parent_property)
Override to create properties of the given picked object(s).
void setMessage(const geometry_msgs::PoseStampedConstPtr &message)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:281
#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 void setReadOnly(bool read_only)
Overridden from Property to propagate read-only-ness to children.
virtual void setColor(float r, float g, float b, float a)
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:86
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
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.
virtual void reset()
Called to tell the display to clear its state.
virtual void setOrientation(const Ogre::Quaternion &orientation)
Set the orientation.
Definition: arrow.cpp:116
Shape * getXShape()
Definition: axes.h:97
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:58
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
Definition: display.h:261
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:530
Property specialized for string values.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
FloatProperty * axes_radius_property_
Definition: pose_display.h:102
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:69
Shape * getShaft()
Definition: arrow.h:150
virtual ~PoseDisplay()
bool initialized() const
Returns true if the display has been initialized.
Definition: display.h:247
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
Definition: axes.h:90
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
Definition: property.h:397
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:47
#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:186
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:159
FloatProperty * head_radius_property_
Definition: pose_display.h:96
virtual void onInitialize()
Override this function to do subclass-specific initialization.
PoseDisplaySelectionHandler(PoseDisplay *display, DisplayContext *context)
void getAABBs(const Picked &obj, V_AABB &aabbs)
Shape * getZShape()
Definition: axes.h:99
Ogre::Entity * getEntity()
Definition: shape.h:104


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat Apr 27 2019 02:33:42