pose_array_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, 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 <OgreManualObject.h>
31 #include <OgreSceneManager.h>
32 #include <OgreSceneNode.h>
33 
34 #include <rviz/display_context.h>
35 #include <rviz/frame_manager.h>
39 #include <rviz/validate_floats.h>
42 #include <rviz/ogre_helpers/axes.h>
43 
45 
46 namespace rviz
47 {
48 namespace
49 {
50 struct ShapeType
51 {
52  enum
53  {
54  Arrow2d,
55  Arrow3d,
56  Axes,
57  };
58 };
59 
60 Ogre::Vector3 vectorRosToOgre(geometry_msgs::Point const& point)
61 {
62  return Ogre::Vector3(point.x, point.y, point.z);
63 }
64 
65 Ogre::Quaternion quaternionRosToOgre(geometry_msgs::Quaternion const& quaternion)
66 {
67  Ogre::Quaternion q;
68  normalizeQuaternion(quaternion, q);
69  return q;
70 }
71 } // namespace
72 
73 PoseArrayDisplay::PoseArrayDisplay() : manual_object_(nullptr)
74 {
75  shape_property_ = new EnumProperty("Shape", "Arrow (Flat)", "Shape to display the pose as.", this,
77 
78  arrow_color_property_ = new ColorProperty("Color", QColor(255, 25, 0), "Color to draw the arrows.",
80 
82  new FloatProperty("Alpha", 1, "Amount of transparency to apply to the displayed poses.", this,
84 
85  arrow2d_length_property_ = new FloatProperty("Arrow Length", 0.3, "Length of the arrows.", this,
87 
89  new FloatProperty("Head Radius", 0.03, "Radius of the arrow's head, in meters.", this,
91 
93  new FloatProperty("Head Length", 0.07, "Length of the arrow's head, in meters.", this,
95 
97  new FloatProperty("Shaft Radius", 0.01, "Radius of the arrow's shaft, in meters.", this,
99 
101  new FloatProperty("Shaft Length", 0.23, "Length of the arrow's shaft, in meters.", this,
103 
104  axes_length_property_ = new FloatProperty("Axes Length", 0.3, "Length of each axis, in meters.", this,
106 
107  axes_radius_property_ = new FloatProperty("Axes Radius", 0.01, "Radius of each axis, in meters.", this,
109 
110  shape_property_->addOption("Arrow (Flat)", ShapeType::Arrow2d);
111  shape_property_->addOption("Arrow (3D)", ShapeType::Arrow3d);
112  shape_property_->addOption("Axes", ShapeType::Axes);
115 }
116 
118 {
119  if (initialized())
120  {
121  scene_manager_->destroyManualObject(manual_object_);
122  }
123 }
124 
126 {
128  manual_object_ = scene_manager_->createManualObject();
129  manual_object_->setDynamic(true);
130  scene_node_->attachObject(manual_object_);
131  arrow_node_ = scene_node_->createChildSceneNode();
132  axes_node_ = scene_node_->createChildSceneNode();
134 }
135 
136 bool validateFloats(const geometry_msgs::PoseArray& msg)
137 {
138  return validateFloats(msg.poses);
139 }
140 
141 void PoseArrayDisplay::processMessage(const geometry_msgs::PoseArray::ConstPtr& msg)
142 {
143  if (!validateFloats(*msg))
144  {
146  "Message contained invalid floating point values (nans or infs)");
147  return;
148  }
149 
150  if (!validateQuaternions(msg->poses))
151  {
152  ROS_WARN_ONCE_NAMED("quaternions",
153  "PoseArray msg received on topic '%s' contains unnormalized quaternions. "
154  "This warning will only be output once but may be true for others; "
155  "enable DEBUG messages for ros.rviz.quaternions to see more details.",
156  topic_property_->getTopicStd().c_str());
157  ROS_DEBUG_NAMED("quaternions",
158  "PoseArray msg received on topic '%s' contains unnormalized quaternions.",
159  topic_property_->getTopicStd().c_str());
160  }
161 
162  if (!setTransform(msg->header))
163  {
164  setStatus(StatusProperty::Error, "Topic", "Failed to look up transform");
165  return;
166  }
167 
168  poses_.resize(msg->poses.size());
169  for (std::size_t i = 0; i < msg->poses.size(); ++i)
170  {
171  poses_[i].position = vectorRosToOgre(msg->poses[i].position);
172  poses_[i].orientation = quaternionRosToOgre(msg->poses[i].orientation);
173  }
174 
175  updateDisplay();
177 }
178 
179 bool PoseArrayDisplay::setTransform(std_msgs::Header const& header)
180 {
181  Ogre::Vector3 position;
182  Ogre::Quaternion orientation;
183  if (!context_->getFrameManager()->getTransform(header, position, orientation))
184  {
185  ROS_ERROR("Error transforming pose '%s' from frame '%s' to frame '%s'", qPrintable(getName()),
186  header.frame_id.c_str(), qPrintable(fixed_frame_));
187  return false;
188  }
189  scene_node_->setPosition(position);
190  scene_node_->setOrientation(orientation);
191  return true;
192 }
193 
195 {
196  manual_object_->clear();
197 
198  Ogre::ColourValue color = arrow_color_property_->getOgreColor();
199  color.a = arrow_alpha_property_->getFloat();
201  size_t num_poses = poses_.size();
202  manual_object_->estimateVertexCount(num_poses * 6);
203  manual_object_->begin("BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_LIST,
204  Ogre::ResourceGroupManager::INTERNAL_RESOURCE_GROUP_NAME);
205  for (size_t i = 0; i < num_poses; ++i)
206  {
207  const Ogre::Vector3& pos = poses_[i].position;
208  const Ogre::Quaternion& orient = poses_[i].orientation;
209  Ogre::Vector3 vertices[6];
210  vertices[0] = pos; // back of arrow
211  vertices[1] = pos + orient * Ogre::Vector3(length, 0, 0); // tip of arrow
212  vertices[2] = vertices[1];
213  vertices[3] = pos + orient * Ogre::Vector3(0.75 * length, 0.2 * length, 0);
214  vertices[4] = vertices[1];
215  vertices[5] = pos + orient * Ogre::Vector3(0.75 * length, -0.2 * length, 0);
216 
217  for (int i = 0; i < 6; ++i)
218  {
219  manual_object_->position(vertices[i]);
220  manual_object_->colour(color);
221  }
222  }
223  manual_object_->end();
224 }
225 
227 {
228  int shape = shape_property_->getOptionInt();
229  switch (shape)
230  {
231  case ShapeType::Arrow2d:
232  updateArrows2d();
233  arrows3d_.clear();
234  axes_.clear();
235  break;
236  case ShapeType::Arrow3d:
237  updateArrows3d();
238  manual_object_->clear();
239  axes_.clear();
240  break;
241  case ShapeType::Axes:
242  updateAxes();
243  manual_object_->clear();
244  arrows3d_.clear();
245  break;
246  }
247 }
248 
250 {
251  while (arrows3d_.size() < poses_.size())
252  arrows3d_.push_back(makeArrow3d());
253  while (arrows3d_.size() > poses_.size())
254  arrows3d_.pop_back();
255 
256  Ogre::Quaternion adjust_orientation(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y);
257  for (std::size_t i = 0; i < poses_.size(); ++i)
258  {
259  arrows3d_[i].setPosition(poses_[i].position);
260  arrows3d_[i].setOrientation(poses_[i].orientation * adjust_orientation);
261  }
262 }
263 
265 {
266  while (axes_.size() < poses_.size())
267  axes_.push_back(makeAxes());
268  while (axes_.size() > poses_.size())
269  axes_.pop_back();
270  for (std::size_t i = 0; i < poses_.size(); ++i)
271  {
272  axes_[i].setPosition(poses_[i].position);
273  axes_[i].setOrientation(poses_[i].orientation);
274  }
275 }
276 
278 {
279  Ogre::ColourValue color = arrow_color_property_->getOgreColor();
280  color.a = arrow_alpha_property_->getFloat();
281 
282  Arrow* arrow =
286 
287  arrow->setColor(color);
288  return arrow;
289 }
290 
292 {
295 }
296 
298 {
299  MFDClass::reset();
300  if (manual_object_)
301  {
302  manual_object_->clear();
303  }
304  arrows3d_.clear();
305  axes_.clear();
306 }
307 
309 {
310  int shape = shape_property_->getOptionInt();
311  bool use_arrow2d = shape == ShapeType::Arrow2d;
312  bool use_arrow3d = shape == ShapeType::Arrow3d;
313  bool use_arrow = use_arrow2d || use_arrow3d;
314  bool use_axes = shape == ShapeType::Axes;
315 
316  arrow_color_property_->setHidden(!use_arrow);
317  arrow_alpha_property_->setHidden(!use_arrow);
318 
319  arrow2d_length_property_->setHidden(!use_arrow2d);
320 
325 
326  axes_length_property_->setHidden(!use_axes);
327  axes_radius_property_->setHidden(!use_axes);
328 
329  if (initialized())
330  updateDisplay();
331 }
332 
334 {
335  int shape = shape_property_->getOptionInt();
336  Ogre::ColourValue color = arrow_color_property_->getOgreColor();
337  color.a = arrow_alpha_property_->getFloat();
338 
339  if (shape == ShapeType::Arrow2d)
340  {
341  updateArrows2d();
342  }
343  else if (shape == ShapeType::Arrow3d)
344  {
345  for (std::size_t i = 0; i < arrows3d_.size(); ++i)
346  {
347  arrows3d_[i].setColor(color);
348  }
349  }
351 }
352 
354 {
355  updateArrows2d();
357 }
358 
360 {
361  for (std::size_t i = 0; i < poses_.size(); ++i)
362  {
367  }
369 }
370 
372 {
373  for (std::size_t i = 0; i < poses_.size(); ++i)
374  {
376  }
378 }
379 
380 } // namespace rviz
381 
rviz::PoseArrayDisplay::arrow2d_length_property_
FloatProperty * arrow2d_length_property_
Definition: pose_array_display.h:92
rviz::PoseArrayDisplay::makeAxes
Axes * makeAxes()
Definition: pose_array_display.cpp:291
rviz::PoseArrayDisplay::updateAxesGeometry
void updateAxesGeometry()
Update the axes geometry.
Definition: pose_array_display.cpp:371
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::PoseArrayDisplay::updateArrowColor
void updateArrowColor()
Update the arrow color.
Definition: pose_array_display.cpp:333
rviz::PoseArrayDisplay::arrow_color_property_
ColorProperty * arrow_color_property_
Definition: pose_array_display.h:89
rviz::PoseArrayDisplay::processMessage
void processMessage(const geometry_msgs::PoseArray::ConstPtr &msg) override
Definition: pose_array_display.cpp:141
rviz::MessageFilterDisplay< geometry_msgs::PoseArray >::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:569
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
rviz::PoseArrayDisplay::arrow3d_shaft_length_property_
FloatProperty * arrow3d_shaft_length_property_
Definition: pose_array_display.h:97
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::FloatProperty::setMax
void setMax(float max)
Definition: float_property.cpp:57
rviz::PoseArrayDisplay::updateArrow3dGeometry
void updateArrow3dGeometry()
Update the 3D arrow geometry.
Definition: pose_array_display.cpp:359
rviz::validateFloats
bool validateFloats(const sensor_msgs::CameraInfo &msg)
Definition: camera_display.cpp:72
float_property.h
ROS_WARN_ONCE_NAMED
#define ROS_WARN_ONCE_NAMED(name,...)
rviz::PoseArrayDisplay::shape_property_
EnumProperty * shape_property_
Definition: pose_array_display.h:88
rviz::PoseArrayDisplay::updateDisplay
void updateDisplay()
Definition: pose_array_display.cpp:226
rviz::PoseArrayDisplay::setTransform
bool setTransform(std_msgs::Header const &header)
Definition: pose_array_display.cpp:179
rviz::Display::fixed_frame_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
validate_quaternions.h
rviz::PoseArrayDisplay::arrow_alpha_property_
FloatProperty * arrow_alpha_property_
Definition: pose_array_display.h:90
rviz::PoseArrayDisplay::arrows3d_
boost::ptr_vector< Arrow > arrows3d_
Definition: pose_array_display.h:81
pose_array_display.h
rviz::FloatProperty::setMin
void setMin(float min)
Definition: float_property.cpp:51
rviz::ColorProperty
Definition: color_property.h:40
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::PoseArrayDisplay::updateArrow2dGeometry
void updateArrow2dGeometry()
Update the flat arrow geometry.
Definition: pose_array_display.cpp:353
rviz::PoseArrayDisplay::arrow_node_
Ogre::SceneNode * arrow_node_
Definition: pose_array_display.h:84
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::normalizeQuaternion
float normalizeQuaternion(float &w, float &x, float &y, float &z)
Definition: validate_quaternions.h:66
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::PoseArrayDisplay::arrow3d_head_length_property_
FloatProperty * arrow3d_head_length_property_
Definition: pose_array_display.h:95
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::PoseArrayDisplay
Displays a geometry_msgs/PoseArray message as a bunch of line-drawn arrows.
Definition: pose_array_display.h:53
rviz::Display::scene_manager_
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
Definition: display.h:292
arrow.h
rviz::PoseArrayDisplay::updateArrows2d
void updateArrows2d()
Definition: pose_array_display.cpp:194
rviz::PoseArrayDisplay::makeArrow3d
Arrow * makeArrow3d()
Definition: pose_array_display.cpp:277
rviz::_RosTopicDisplay::topic_property_
RosTopicProperty * topic_property_
Definition: message_filter_display.h:78
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
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::RosTopicProperty::getTopicStd
std::string getTopicStd() const
Definition: ros_topic_property.h:85
rviz::PoseArrayDisplay::updateShapeChoice
void updateShapeChoice()
Update the interface and visible shapes based on the selected shape type.
Definition: pose_array_display.cpp:308
rviz::PoseArrayDisplay::axes_length_property_
FloatProperty * axes_length_property_
Definition: pose_array_display.h:99
rviz::MessageFilterDisplay< geometry_msgs::PoseArray >::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::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::PoseArrayDisplay::arrow3d_head_radius_property_
FloatProperty * arrow3d_head_radius_property_
Definition: pose_array_display.h:94
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
rviz::PoseArrayDisplay::axes_
boost::ptr_vector< Axes > axes_
Definition: pose_array_display.h:82
rviz::PoseArrayDisplay::axes_node_
Ogre::SceneNode * axes_node_
Definition: pose_array_display.h:85
rviz::PoseArrayDisplay::updateAxes
void updateAxes()
Definition: pose_array_display.cpp:264
rviz::PoseArrayDisplay::updateArrows3d
void updateArrows3d()
Definition: pose_array_display.cpp:249
display_context.h
rviz::PoseArrayDisplay::manual_object_
Ogre::ManualObject * manual_object_
Definition: pose_array_display.h:86
rviz::PoseArrayDisplay::axes_radius_property_
FloatProperty * axes_radius_property_
Definition: pose_array_display.h:100
header
const std::string header
rviz::PoseArrayDisplay::PoseArrayDisplay
PoseArrayDisplay()
Definition: pose_array_display.cpp:73
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::PoseArrayDisplay::onInitialize
void onInitialize() override
Override this function to do subclass-specific initialization.
Definition: pose_array_display.cpp:125
rviz::PoseArrayDisplay::arrow3d_shaft_radius_property_
FloatProperty * arrow3d_shaft_radius_property_
Definition: pose_array_display.h:96
rviz::PoseArrayDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: pose_array_display.cpp:297
rviz::ColorProperty::getOgreColor
Ogre::ColourValue getOgreColor() const
Definition: color_property.h:83
rviz::PoseArrayDisplay::~PoseArrayDisplay
~PoseArrayDisplay() override
Definition: pose_array_display.cpp:117
enum_property.h
rviz::PoseArrayDisplay::poses_
std::vector< OgrePose > poses_
Definition: pose_array_display.h:80


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Thu May 16 2024 02:30:49