tf_trajectory_display.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <boost/format.hpp>
37 #include "tf_trajectory_display.h"
38 
39 namespace jsk_rviz_plugins
40 {
41  #define MAX_ELEMENTS_PER_LINE (65536 / 4) // from ros-visualization/rviz/src/rviz/ogre_helpers/billboard_line.cpp
43  : Display()
44  {
45  frame_property_ = new rviz::TfFrameProperty("frame", "",
46  "frame to visualize trajectory",
47  this,
48  NULL,
49  false,
50  SLOT(updateFrame()));
51  duration_property_ = new rviz::FloatProperty("duration", 10.0,
52  "duration to visualize trajectory",
53  this, SLOT(updateDuration()));
54  line_width_property_ = new rviz::FloatProperty("line_width", 0.01,
55  "line width",
56  this, SLOT(updateLineWidth()));
57  color_property_ = new rviz::ColorProperty("color", QColor(25, 255, 240),
58  "color of trajectory",
59  this, SLOT(updateColor()));
60  duration_property_->setMin(0.0);
61  line_width_property_->setMin(0.0);
62  }
63 
65  {
66  delete line_width_property_;
67  delete frame_property_;
68  delete duration_property_;
69  delete color_property_;
70  delete line_;
71  }
72 
74  {
77  updateFrame();
79  updateColor();
81  }
82 
84  {
85  frame_ = frame_property_->getFrame().toStdString();
86  trajectory_.clear();
87  }
88 
90  {
92  }
93 
95  {
97  }
98 
100  {
101  line_->clear();
102  trajectory_.clear();
103  }
104 
106  {
108  }
109 
111  {
112  line_->clear();
113  trajectory_.clear();
114  }
115 
116  void TFTrajectoryDisplay::update(float wall_dt, float ros_dt)
117  {
118  if (frame_.empty()) {
119  return;
120  }
121  std::string fixed_frame_id = context_->getFrameManager()->getFixedFrame();
122  if (fixed_frame_ != fixed_frame_id) {
123  fixed_frame_ = fixed_frame_id;
124  line_->clear();
125  trajectory_.clear();
126  return;
127  }
128  fixed_frame_ = fixed_frame_id;
130  std_msgs::Header header;
131  header.stamp = ros::Time(0.0);
132  header.frame_id = frame_;
133  Ogre::Vector3 position;
134  Ogre::Quaternion orientation;
136  header, position, orientation)) {
138  (boost::format("Failed transforming from frame '%s' to frame '%s'")
139  % header.frame_id.c_str() % fixed_frame_id.c_str()).str().c_str());
140  return;
141  }
142  setStatus(rviz::StatusProperty::Ok, "transformation", "Ok");
143  geometry_msgs::PointStamped new_point;
144  new_point.header.stamp = now;
145  new_point.point.x = position[0];
146  new_point.point.y = position[1];
147  new_point.point.z = position[2];
148  trajectory_.push_back(new_point);
149  // check old data, is it too slow??
150  for (std::vector<geometry_msgs::PointStamped>::iterator it = trajectory_.begin();
151  it != trajectory_.end();) {
152  ros::Duration duration = now - it->header.stamp;
153  if (duration.toSec() > duration_) {
154  it = trajectory_.erase(it);
155  }
156  else {
157  break;
158  }
159  }
160  line_->clear();
161  // split into multiple lines if the trajectory size exceeds MAX_ELEMENTS_PER_LINE (https://github.com/ros-visualization/rviz/issues/1107)
165  line_->setColor(color_.red() * 255.0, color_.green() * 255.0, color_.blue() * 255.0, 255.0);
166  for (size_t i = 0; i < trajectory_.size(); i++) {
167  Ogre::Vector3 p;
168  p[0] = trajectory_[i].point.x;
169  p[1] = trajectory_[i].point.y;
170  p[2] = trajectory_[i].point.z;
171  line_->addPoint(p);
172  }
173  }
174 }
175 
rviz::BillboardLine::clear
void clear()
rviz::BillboardLine
jsk_rviz_plugins::TFTrajectoryDisplay::TFTrajectoryDisplay
TFTrajectoryDisplay()
Definition: tf_trajectory_display.cpp:74
jsk_rviz_plugins::TFTrajectoryDisplay::line_width_
float line_width_
Definition: tf_trajectory_display.h:138
rviz::BillboardLine::setLineWidth
void setLineWidth(float width)
jsk_rviz_plugins::TFTrajectoryDisplay::updateDuration
void updateDuration()
Definition: tf_trajectory_display.cpp:121
rviz::ColorProperty::getColor
virtual QColor getColor() const
jsk_rviz_plugins::TFTrajectoryDisplay::updateFrame
void updateFrame()
Definition: tf_trajectory_display.cpp:115
jsk_rviz_plugins::TFTrajectoryDisplay::updateLineWidth
void updateLineWidth()
Definition: tf_trajectory_display.cpp:137
jsk_rviz_plugins::TFTrajectoryDisplay::trajectory_
std::vector< geometry_msgs::PointStamped > trajectory_
Definition: tf_trajectory_display.h:133
bounding_box_sample.now
now
Definition: bounding_box_sample.py:18
rviz::StatusProperty::Error
Error
p
p
jsk_rviz_plugins::TFTrajectoryDisplay::color_property_
rviz::ColorProperty * color_property_
Definition: tf_trajectory_display.h:130
rviz::BillboardLine::setMaxPointsPerLine
void setMaxPointsPerLine(uint32_t max)
jsk_rviz_plugins::TFTrajectoryDisplay::updateColor
void updateColor()
Definition: tf_trajectory_display.cpp:126
jsk_rviz_plugins::TFTrajectoryDisplay::duration_
float duration_
Definition: tf_trajectory_display.h:136
rviz::DisplayContext::getSceneManager
virtual Ogre::SceneManager * getSceneManager() const=0
rviz::ColorProperty
rviz::Display
rviz::FloatProperty
jsk_rviz_plugins::TFTrajectoryDisplay::duration_property_
rviz::FloatProperty * duration_property_
Definition: tf_trajectory_display.h:129
rviz::FrameManager::getTime
ros::Time getTime()
class_list_macros.h
jsk_rviz_plugins::TFTrajectoryDisplay
Definition: tf_trajectory_display.h:84
rviz::Display::setStatus
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
jsk_rviz_plugins::TFTrajectoryDisplay::update
virtual void update(float wall_dt, float ros_dt)
Definition: tf_trajectory_display.cpp:148
rviz::FrameManager::getFixedFrame
const std::string & getFixedFrame()
jsk_rviz_plugins::TFTrajectoryDisplay::onInitialize
virtual void onInitialize()
Definition: tf_trajectory_display.cpp:105
rviz::FloatProperty::getFloat
virtual float getFloat() const
jsk_rviz_plugins::TFTrajectoryDisplay::onDisable
virtual void onDisable()
Definition: tf_trajectory_display.cpp:142
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
rviz::StatusProperty::Ok
Ok
tf_trajectory_display.h
MAX_ELEMENTS_PER_LINE
#define MAX_ELEMENTS_PER_LINE
Definition: tf_trajectory_display.cpp:73
rviz::BillboardLine::setNumLines
void setNumLines(uint32_t num)
polygon_array_sample.header
header
Definition: polygon_array_sample.py:58
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const=0
rviz::TfFrameProperty
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
rviz::Display::context_
DisplayContext * context_
ros::Time
jsk_rviz_plugins::TFTrajectoryDisplay::line_width_property_
rviz::FloatProperty * line_width_property_
Definition: tf_trajectory_display.h:131
rviz::TfFrameProperty::getFrame
QString getFrame() const
jsk_rviz_plugins::TFTrajectoryDisplay::onEnable
virtual void onEnable()
Definition: tf_trajectory_display.cpp:131
jsk_rviz_plugins::TFTrajectoryDisplay::color_
QColor color_
Definition: tf_trajectory_display.h:137
jsk_rviz_plugins::TFTrajectoryDisplay::~TFTrajectoryDisplay
virtual ~TFTrajectoryDisplay()
Definition: tf_trajectory_display.cpp:96
jsk_rviz_plugins::TFTrajectoryDisplay::fixed_frame_
std::string fixed_frame_
Definition: tf_trajectory_display.h:135
jsk_rviz_plugins::TFTrajectoryDisplay::line_
rviz::BillboardLine * line_
Definition: tf_trajectory_display.h:132
rviz::TfFrameProperty::setFrameManager
void setFrameManager(FrameManager *frame_manager)
DurationBase< Duration >::toSec
double toSec() const
jsk_rviz_plugins::TargetVisualizerDisplay::color_property_
rviz::ColorProperty * color_property_
Definition: target_visualizer_display.h:149
ros::Duration
jsk_rviz_plugins::TFTrajectoryDisplay::frame_property_
rviz::TfFrameProperty * frame_property_
Definition: tf_trajectory_display.h:128
jsk_rviz_plugins
Definition: __init__.py:1
rviz::BillboardLine::setColor
void setColor(float r, float g, float b, float a) override
jsk_rviz_plugins::TFTrajectoryDisplay::frame_
std::string frame_
Definition: tf_trajectory_display.h:134
rviz::BillboardLine::addPoint
void addPoint(const Ogre::Vector3 &point)
jsk_rviz_plugins::TargetVisualizerDisplay::updateColor
void updateColor()
Definition: target_visualizer_display.cpp:211


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Jan 22 2024 03:47:13