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,
76  SLOT(updateShapeChoice()));
77 
78  arrow_color_property_ = new ColorProperty("Color", QColor(255, 25, 0), "Color to draw the arrows.",
79  this, SLOT(updateArrowColor()));
80 
82  new FloatProperty("Alpha", 1, "Amount of transparency to apply to the displayed poses.", this,
83  SLOT(updateArrowColor()));
84 
85  arrow2d_length_property_ = new FloatProperty("Arrow Length", 0.3, "Length of the arrows.", this,
86  SLOT(updateArrow2dGeometry()));
87 
89  new FloatProperty("Head Radius", 0.03, "Radius of the arrow's head, in meters.", this,
90  SLOT(updateArrow3dGeometry()));
91 
93  new FloatProperty("Head Length", 0.07, "Length of the arrow's head, in meters.", this,
94  SLOT(updateArrow3dGeometry()));
95 
97  new FloatProperty("Shaft Radius", 0.01, "Radius of the arrow's shaft, in meters.", this,
98  SLOT(updateArrow3dGeometry()));
99 
101  new FloatProperty("Shaft Length", 0.23, "Length of the arrow's shaft, in meters.", this,
102  SLOT(updateArrow3dGeometry()));
103 
104  axes_length_property_ = new FloatProperty("Axes Length", 0.3, "Length of each axis, in meters.", this,
105  SLOT(updateAxesGeometry()));
106 
107  axes_radius_property_ = new FloatProperty("Axes Radius", 0.01, "Radius of each axis, in meters.", this,
108  SLOT(updateAxesGeometry()));
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  for (size_t i = 0; i < num_poses; ++i)
205  {
206  const Ogre::Vector3& pos = poses_[i].position;
207  const Ogre::Quaternion& orient = poses_[i].orientation;
208  Ogre::Vector3 vertices[6];
209  vertices[0] = pos; // back of arrow
210  vertices[1] = pos + orient * Ogre::Vector3(length, 0, 0); // tip of arrow
211  vertices[2] = vertices[1];
212  vertices[3] = pos + orient * Ogre::Vector3(0.75 * length, 0.2 * length, 0);
213  vertices[4] = vertices[1];
214  vertices[5] = pos + orient * Ogre::Vector3(0.75 * length, -0.2 * length, 0);
215 
216  for (int i = 0; i < 6; ++i)
217  {
218  manual_object_->position(vertices[i]);
219  manual_object_->colour(color);
220  }
221  }
222  manual_object_->end();
223 }
224 
226 {
227  int shape = shape_property_->getOptionInt();
228  switch (shape)
229  {
230  case ShapeType::Arrow2d:
231  updateArrows2d();
232  arrows3d_.clear();
233  axes_.clear();
234  break;
235  case ShapeType::Arrow3d:
236  updateArrows3d();
237  manual_object_->clear();
238  axes_.clear();
239  break;
240  case ShapeType::Axes:
241  updateAxes();
242  manual_object_->clear();
243  arrows3d_.clear();
244  break;
245  }
246 }
247 
249 {
250  while (arrows3d_.size() < poses_.size())
251  arrows3d_.push_back(makeArrow3d());
252  while (arrows3d_.size() > poses_.size())
253  arrows3d_.pop_back();
254 
255  Ogre::Quaternion adjust_orientation(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y);
256  for (std::size_t i = 0; i < poses_.size(); ++i)
257  {
258  arrows3d_[i].setPosition(poses_[i].position);
259  arrows3d_[i].setOrientation(poses_[i].orientation * adjust_orientation);
260  }
261 }
262 
264 {
265  while (axes_.size() < poses_.size())
266  axes_.push_back(makeAxes());
267  while (axes_.size() > poses_.size())
268  axes_.pop_back();
269  for (std::size_t i = 0; i < poses_.size(); ++i)
270  {
271  axes_[i].setPosition(poses_[i].position);
272  axes_[i].setOrientation(poses_[i].orientation);
273  }
274 }
275 
277 {
278  Ogre::ColourValue color = arrow_color_property_->getOgreColor();
279  color.a = arrow_alpha_property_->getFloat();
280 
281  Arrow* arrow =
285 
286  arrow->setColor(color);
287  return arrow;
288 }
289 
291 {
294 }
295 
297 {
298  MFDClass::reset();
299  if (manual_object_)
300  {
301  manual_object_->clear();
302  }
303  arrows3d_.clear();
304  axes_.clear();
305 }
306 
308 {
309  int shape = shape_property_->getOptionInt();
310  bool use_arrow2d = shape == ShapeType::Arrow2d;
311  bool use_arrow3d = shape == ShapeType::Arrow3d;
312  bool use_arrow = use_arrow2d || use_arrow3d;
313  bool use_axes = shape == ShapeType::Axes;
314 
315  arrow_color_property_->setHidden(!use_arrow);
316  arrow_alpha_property_->setHidden(!use_arrow);
317 
318  arrow2d_length_property_->setHidden(!use_arrow2d);
319 
324 
325  axes_length_property_->setHidden(!use_axes);
326  axes_radius_property_->setHidden(!use_axes);
327 
328  if (initialized())
329  updateDisplay();
330 }
331 
333 {
334  int shape = shape_property_->getOptionInt();
335  Ogre::ColourValue color = arrow_color_property_->getOgreColor();
336  color.a = arrow_alpha_property_->getFloat();
337 
338  if (shape == ShapeType::Arrow2d)
339  {
340  updateArrows2d();
341  }
342  else if (shape == ShapeType::Arrow3d)
343  {
344  for (std::size_t i = 0; i < arrows3d_.size(); ++i)
345  {
346  arrows3d_[i].setColor(color);
347  }
348  }
350 }
351 
353 {
354  updateArrows2d();
356 }
357 
359 {
360  for (std::size_t i = 0; i < poses_.size(); ++i)
361  {
366  }
368 }
369 
371 {
372  for (std::size_t i = 0; i < poses_.size(); ++i)
373  {
375  }
377 }
378 
379 } // namespace rviz
380 
void setMin(float min)
FloatProperty * arrow3d_head_length_property_
void reset() override
Called to tell the display to clear its state.
void setMax(float max)
void updateAxesGeometry()
Update the axes geometry.
void updateShapeChoice()
Update the interface and visible shapes based on the selected shape type.
ColorProperty * arrow_color_property_
FloatProperty * arrow2d_length_property_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition: display.h:287
bool setTransform(std_msgs::Header const &header)
Displays a geometry_msgs/PoseArray message as a bunch of line-drawn arrows.
Ogre::ColourValue getOgreColor() const
RosTopicProperty * topic_property_
FloatProperty * axes_radius_property_
void updateArrow2dGeometry()
Update the flat arrow geometry.
Property specialized to enforce floating point max/min.
std::string getTopicStd() const
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
FloatProperty * arrow3d_shaft_radius_property_
#define ROS_DEBUG_NAMED(name,...)
std::vector< OgrePose > poses_
FloatProperty * arrow_alpha_property_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void addOption(const QString &option, int value=0)
void onInitialize() override
Override this function to do subclass-specific initialization.
void updateArrowColor()
Update the arrow color.
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:164
void processMessage(const geometry_msgs::PoseArray::ConstPtr &msg) override
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
FloatProperty * axes_length_property_
FloatProperty * arrow3d_shaft_length_property_
float normalizeQuaternion(float &w, float &x, float &y, float &z)
#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
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
Definition: property.cpp:552
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)
virtual float getFloat() const
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.
EnumProperty * shape_property_
void updateArrow3dGeometry()
Update the 3D arrow geometry.
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:59
boost::ptr_vector< Arrow > arrows3d_
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
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 * arrow_node_
FloatProperty * arrow3d_head_radius_property_
boost::ptr_vector< Axes > axes_
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Enum property.
Definition: enum_property.h:46
#define ROS_ERROR(...)
Ogre::ManualObject * manual_object_
Ogre::SceneNode * axes_node_
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


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