path_with_velocity_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 <algorithm>
31 #include <vector>
32 
33 #include <boost/bind.hpp>
34 
35 #include <OgreBillboardSet.h>
36 #include <OgreManualObject.h>
37 #include <OgreMatrix4.h>
38 #include <OgreSceneManager.h>
39 #include <OgreSceneNode.h>
40 
41 #include <rviz/display_context.h>
42 #include <rviz/frame_manager.h>
49 
50 #include <trajectory_tracker_msgs/PathWithVelocity.h>
51 #include <trajectory_tracker_msgs/PoseStampedWithVelocity.h>
54 
55 #include <rviz/validate_floats.h>
56 #ifdef HAVE_VALIDATE_QUATERNION_H
58 #endif
59 
61 {
63 {
65  "Line Style", "Lines",
66  "The rendering operation to use to draw the grid lines.",
67  this, SLOT(updateStyle()));
68 
69  style_property_->addOption("Lines", LINES);
70  style_property_->addOption("Billboards", BILLBOARDS);
71 
73  "Line Width", 0.03,
74  "The width, in meters, of each path line."
75  "Only works with the 'Billboards' style.",
76  this, SLOT(updateLineWidth()), this);
79 
81  "Color", QColor(25, 255, 0),
82  "Color to draw the path.", this);
83 
85  "Alpha", 1.0,
86  "Amount of transparency to apply to the path.", this);
87 
89  "Buffer Length", 1,
90  "Number of paths to display.",
91  this, SLOT(updateBufferLength()));
93 
95  "Offset", Ogre::Vector3::ZERO,
96  "Allows you to offset the path from the origin of the reference frame. In meters.",
97  this, SLOT(updateOffset()));
98 
100  "Pose Style", "None", "Shape to display the pose as.",
101  this, SLOT(updatePoseStyle()));
105 
107  "Length", 0.3,
108  "Length of the axes.",
109  this, SLOT(updatePoseAxisGeometry()));
111  "Radius", 0.03,
112  "Radius of the axes.",
113  this, SLOT(updatePoseAxisGeometry()));
114 
116  "Pose Color",
117  QColor(255, 85, 255),
118  "Color to draw the poses.",
119  this, SLOT(updatePoseArrowColor()));
121  "Shaft Length", 0.1,
122  "Length of the arrow shaft.",
123  this,
124  SLOT(updatePoseArrowGeometry()));
126  "Head Length", 0.2,
127  "Length of the arrow head.",
128  this,
129  SLOT(updatePoseArrowGeometry()));
131  "Shaft Diameter", 0.1,
132  "Diameter of the arrow shaft.",
133  this,
134  SLOT(updatePoseArrowGeometry()));
136  "Head Diameter", 0.3,
137  "Diameter of the arrow head.",
138  this,
139  SLOT(updatePoseArrowGeometry()));
147 }
148 
150 {
151  destroyObjects();
154 }
155 
157 {
160 }
161 
163 {
164  MFDClass::reset();
166 }
167 
168 void PathWithVelocityDisplay::allocateAxesVector(std::vector<rviz::Axes*>& axes_vect, size_t num)
169 {
170  if (num > axes_vect.size())
171  {
172  for (size_t i = axes_vect.size(); i < num; i++)
173  {
177  axes_vect.push_back(axes);
178  }
179  }
180  else if (num < axes_vect.size())
181  {
182  for (int i = static_cast<int>(axes_vect.size()) - 1; static_cast<int>(num) <= i; i--)
183  {
184  delete axes_vect[i];
185  }
186  axes_vect.resize(num);
187  }
188 }
189 
190 void PathWithVelocityDisplay::allocateArrowVector(std::vector<rviz::Arrow*>& arrow_vect, size_t num)
191 {
192  if (num > arrow_vect.size())
193  {
194  for (size_t i = arrow_vect.size(); i < num; i++)
195  {
197  arrow_vect.push_back(arrow);
198  }
199  }
200  else if (num < arrow_vect.size())
201  {
202  for (int i = static_cast<int>(arrow_vect.size()) - 1; static_cast<int>(num) <= i; i--)
203  {
204  delete arrow_vect[i];
205  }
206  arrow_vect.resize(num);
207  }
208 }
209 
211 {
212  for (size_t i = 0; i < axes_chain_.size(); i++)
213  {
215  }
216  axes_chain_.resize(0);
217 }
218 
220 {
221  for (size_t i = 0; i < arrow_chain_.size(); i++)
222  {
224  }
225  arrow_chain_.resize(0);
226 }
227 
229 {
231 
232  switch (style)
233  {
234  case LINES:
235  default:
237  break;
238 
239  case BILLBOARDS:
241  break;
242  }
243 
245 }
246 
248 {
250  float line_width = line_width_property_->getFloat();
251 
252  if (style == BILLBOARDS)
253  {
254  for (size_t i = 0; i < billboard_lines_.size(); i++)
255  {
256  rviz::BillboardLine* billboard_line = billboard_lines_[i];
257  if (billboard_line)
258  billboard_line->setLineWidth(line_width);
259  }
260  }
262 }
263 
265 {
266  scene_node_->setPosition(offset_property_->getVector());
268 }
269 
271 {
273  switch (pose_style)
274  {
275  case AXES:
283  break;
284  case ARROWS:
292  break;
293  default:
301  }
303 }
304 
306 {
307  for (size_t i = 0; i < axes_chain_.size(); i++)
308  {
309  std::vector<rviz::Axes*>& axes_vect = axes_chain_[i];
310  for (size_t j = 0; j < axes_vect.size(); j++)
311  {
312  axes_vect[j]->set(pose_axes_length_property_->getFloat(),
314  }
315  }
317 }
318 
320 {
321  QColor color = pose_arrow_color_property_->getColor();
322 
323  for (size_t i = 0; i < arrow_chain_.size(); i++)
324  {
325  std::vector<rviz::Arrow*>& arrow_vect = arrow_chain_[i];
326  for (size_t j = 0; j < arrow_vect.size(); j++)
327  {
328  arrow_vect[j]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
329  }
330  }
332 }
333 
335 {
336  for (size_t i = 0; i < arrow_chain_.size(); i++)
337  {
338  std::vector<rviz::Arrow*>& arrow_vect = arrow_chain_[i];
339  for (size_t j = 0; j < arrow_vect.size(); j++)
340  {
341  arrow_vect[j]->set(pose_arrow_shaft_length_property_->getFloat(),
345  }
346  }
348 }
349 
351 {
352  // Destroy all simple lines, if any
353  for (size_t i = 0; i < manual_objects_.size(); i++)
354  {
355  Ogre::ManualObject*& manual_object = manual_objects_[i];
356  if (manual_object)
357  {
358  manual_object->clear();
359  scene_manager_->destroyManualObject(manual_object);
360  manual_object = NULL; // ensure it doesn't get destroyed again
361  }
362  }
363 
364  // Destroy all billboards, if any
365  for (size_t i = 0; i < billboard_lines_.size(); i++)
366  {
367  rviz::BillboardLine*& billboard_line = billboard_lines_[i];
368  if (billboard_line)
369  {
370  delete billboard_line; // also destroys the corresponding scene node
371  billboard_line = NULL; // ensure it doesn't get destroyed again
372  }
373  }
374 }
375 
377 {
378  // Delete old path objects
379  destroyObjects();
380 
381  // Destroy all axes and arrows
384 
385  // Read options
386  int buffer_length = buffer_length_property_->getInt();
388 
389  // Create new path objects
390  switch (style)
391  {
392  case LINES: // simple lines with fixed width of 1px
393  manual_objects_.resize(buffer_length);
394  for (size_t i = 0; i < manual_objects_.size(); i++)
395  {
396  Ogre::ManualObject* manual_object = scene_manager_->createManualObject();
397  manual_object->setDynamic(true);
398  scene_node_->attachObject(manual_object);
399 
400  manual_objects_[i] = manual_object;
401  }
402  break;
403 
404  case BILLBOARDS: // billboards with configurable width
405  billboard_lines_.resize(buffer_length);
406  for (size_t i = 0; i < billboard_lines_.size(); i++)
407  {
409  billboard_lines_[i] = billboard_line;
410  }
411  break;
412  }
413  axes_chain_.resize(buffer_length);
414  arrow_chain_.resize(buffer_length);
415 }
416 
417 void PathWithVelocityDisplay::processMessage(const trajectory_tracker_msgs::PathWithVelocity::ConstPtr& msg)
418 {
419  // Calculate index of oldest element in cyclic buffer
420  size_t bufferIndex = messages_received_ % buffer_length_property_->getInt();
421 
423  Ogre::ManualObject* manual_object = NULL;
424  rviz::BillboardLine* billboard_line = NULL;
425 
426  // Delete oldest element
427  switch (style)
428  {
429  case LINES:
430  manual_object = manual_objects_[bufferIndex];
431  manual_object->clear();
432  break;
433 
434  case BILLBOARDS:
435  billboard_line = billboard_lines_[bufferIndex];
436  billboard_line->clear();
437  break;
438  }
439 
440  // Check if path contains invalid coordinate values
442  {
443  setStatus(rviz::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)");
444  return;
445  }
446 
447 #ifdef HAVE_VALIDATE_QUATERNION_H
448  if (!trajectory_tracker_rviz_plugins::validateQuaternions(msg->poses))
449  {
451  "quaternions", "Path '%s' contains unnormalized quaternions. "
452  "This warning will only be output once but may be true for others; "
453  "enable DEBUG messages for ros.rviz.quaternions to see more details.",
454  qPrintable(getName()));
456  "quaternions", "Path '%s' contains unnormalized quaternions.",
457  qPrintable(getName()));
458  }
459 #endif
460 
461  // Lookup transform into fixed frame
462  Ogre::Vector3 position;
463  Ogre::Quaternion orientation;
464  if (!context_->getFrameManager()->getTransform(msg->header, position, orientation))
465  {
466  ROS_DEBUG(
467  "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), qPrintable(fixed_frame_));
468  }
469 
470  Ogre::Matrix4 transform(orientation);
471  transform.setTrans(position);
472 
473  // scene_node_->setPosition( position );
474  // scene_node_->setOrientation( orientation );
475 
476  Ogre::ColourValue color = color_property_->getOgreColor();
477  color.a = alpha_property_->getFloat();
478 
479  uint32_t num_points = msg->poses.size();
480  float line_width = line_width_property_->getFloat();
481 
482  switch (style)
483  {
484  case LINES:
485  manual_object->estimateVertexCount(num_points);
486  manual_object->begin("BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP);
487  for (uint32_t i = 0; i < num_points; ++i)
488  {
489  const geometry_msgs::Point& pos = msg->poses[i].pose.position;
490  Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
491  manual_object->position(xpos.x, xpos.y, xpos.z);
492  manual_object->colour(color);
493  }
494 
495  manual_object->end();
496  break;
497 
498  case BILLBOARDS:
499  billboard_line->setNumLines(1);
500  billboard_line->setMaxPointsPerLine(num_points);
501  billboard_line->setLineWidth(line_width);
502 
503  for (uint32_t i = 0; i < num_points; ++i)
504  {
505  const geometry_msgs::Point& pos = msg->poses[i].pose.position;
506  Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
507  billboard_line->addPoint(xpos, color);
508  }
509 
510  break;
511  }
512 
513  // process pose markers
515  std::vector<rviz::Arrow*>& arrow_vect = arrow_chain_[bufferIndex];
516  std::vector<rviz::Axes*>& axes_vect = axes_chain_[bufferIndex];
517 
518  switch (pose_style)
519  {
520  case AXES:
521  allocateAxesVector(axes_vect, num_points);
522  for (uint32_t i = 0; i < num_points; ++i)
523  {
524  const geometry_msgs::Point& pos = msg->poses[i].pose.position;
525  Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
526  axes_vect[i]->setPosition(xpos);
527  Ogre::Quaternion orientation(msg->poses[i].pose.orientation.w,
528  msg->poses[i].pose.orientation.x,
529  msg->poses[i].pose.orientation.y,
530  msg->poses[i].pose.orientation.z);
531  axes_vect[i]->setOrientation(orientation);
532  }
533  break;
534 
535  case ARROWS:
536  allocateArrowVector(arrow_vect, num_points);
537  for (uint32_t i = 0; i < num_points; ++i)
538  {
539  const geometry_msgs::Point& pos = msg->poses[i].pose.position;
540  Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
541 
542  QColor color = pose_arrow_color_property_->getColor();
543  arrow_vect[i]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
544 
545  arrow_vect[i]->set(pose_arrow_shaft_length_property_->getFloat(),
549  arrow_vect[i]->setPosition(xpos);
550  Ogre::Quaternion orientation(msg->poses[i].pose.orientation.w,
551  msg->poses[i].pose.orientation.x,
552  msg->poses[i].pose.orientation.y,
553  msg->poses[i].pose.orientation.z);
554 
555  Ogre::Vector3 dir(1, 0, 0);
556  dir = orientation * dir;
557  arrow_vect[i]->setDirection(dir);
558  }
559  break;
560 
561  default:
562  break;
563  }
565 }
566 
567 } // namespace trajectory_tracker_rviz_plugins
568 
virtual QColor getColor() const
#define NULL
void setMin(float min)
Ogre::ColourValue getOgreColor() const
void addPoint(const Ogre::Vector3 &point)
DisplayContext * context_
bool validateFloats(const trajectory_tracker_msgs::PoseStampedWithVelocity &msg)
virtual int getInt() const
virtual float getFloat() const
Displays a trajectory_tracker_msgs::PathWithVelocity message.
void setMin(int min)
Ogre::SceneNode * scene_node_
QString fixed_frame_
#define ROS_DEBUG_NAMED(name,...)
void processMessage(const trajectory_tracker_msgs::PathWithVelocity::ConstPtr &msg)
Overridden from MessageFilterDisplay.
virtual void addOption(const QString &option, int value=0)
virtual FrameManager * getFrameManager() const =0
void allocateAxesVector(std::vector< rviz::Axes * > &axes_vect, size_t num)
void setNumLines(uint32_t num)
#define ROS_WARN_ONCE_NAMED(name,...)
void setMaxPointsPerLine(uint32_t max)
Ogre::SceneManager * scene_manager_
virtual void queueRender()=0
virtual Ogre::Vector3 getVector() const
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void allocateArrowVector(std::vector< rviz::Arrow * > &arrow_vect, size_t num)
virtual int getOptionInt()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
virtual QString getName() const
void setLineWidth(float width)
#define ROS_DEBUG(...)


trajectory_tracker_rviz_plugins
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 8 2019 19:23:54