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/o2r 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 {
42  : Display()
43  {
44  frame_property_ = new rviz::TfFrameProperty("frame", "",
45  "frame to visualize trajectory",
46  this,
47  NULL,
48  false,
49  SLOT(updateFrame()));
50  duration_property_ = new rviz::FloatProperty("duration", 10.0,
51  "duration to visualize trajectory",
52  this, SLOT(updateDuration()));
53  line_width_property_ = new rviz::FloatProperty("line_width", 0.01,
54  "line width",
55  this, SLOT(updateLineWidth()));
56  color_property_ = new rviz::ColorProperty("color", QColor(25, 255, 240),
57  "color of trajectory",
58  this, SLOT(updateColor()));
61  }
62 
64  {
65  delete line_width_property_;
66  delete frame_property_;
67  delete duration_property_;
68  delete color_property_;
69  delete line_;
70  }
71 
73  {
76  updateFrame();
78  updateColor();
80  }
81 
83  {
84  frame_ = frame_property_->getFrame().toStdString();
85  trajectory_.clear();
86  }
87 
89  {
91  }
92 
94  {
96  }
97 
99  {
100  line_->clear();
101  trajectory_.clear();
102  }
103 
105  {
107  }
108 
110  {
111  line_->clear();
112  trajectory_.clear();
113  }
114 
115  void TFTrajectoryDisplay::update(float wall_dt, float ros_dt)
116  {
117  if (frame_.empty()) {
118  return;
119  }
120  std::string fixed_frame_id = context_->getFrameManager()->getFixedFrame();
121  if (fixed_frame_ != fixed_frame_id) {
122  fixed_frame_ = fixed_frame_id;
123  line_->clear();
124  trajectory_.clear();
125  return;
126  }
127  fixed_frame_ = fixed_frame_id;
129  std_msgs::Header header;
130  header.stamp = ros::Time(0.0);
131  header.frame_id = frame_;
132  Ogre::Vector3 position;
133  Ogre::Quaternion orientation;
135  header, position, orientation)) {
136  setStatus(rviz::StatusProperty::Error, "transformation",
137  (boost::format("Failed transforming from frame '%s' to frame '%s'")
138  % header.frame_id.c_str() % fixed_frame_id.c_str()).str().c_str());
139  return;
140  }
141  setStatus(rviz::StatusProperty::Ok, "transformation", "Ok");
142  geometry_msgs::PointStamped new_point;
143  new_point.header.stamp = now;
144  new_point.point.x = position[0];
145  new_point.point.y = position[1];
146  new_point.point.z = position[2];
147  trajectory_.push_back(new_point);
148  // check old data, is it too slow??
149  for (std::vector<geometry_msgs::PointStamped>::iterator it = trajectory_.begin();
150  it != trajectory_.end();) {
151  ros::Duration duration = now - it->header.stamp;
152  if (duration.toSec() > duration_) {
153  it = trajectory_.erase(it);
154  }
155  else {
156  break;
157  }
158  }
159  line_->clear();
160  line_->setNumLines(1);
163  line_->setColor(color_.red() * 255.0, color_.green() * 255.0, color_.blue() * 255.0, 255.0);
164  for (size_t i = 0; i < trajectory_.size(); i++) {
165  Ogre::Vector3 p;
166  p[0] = trajectory_[i].point.x;
167  p[1] = trajectory_[i].point.y;
168  p[2] = trajectory_[i].point.z;
169  line_->addPoint(p);
170  }
171  }
172 }
173 
virtual QColor getColor() const
#define NULL
void setMin(float min)
std::vector< geometry_msgs::PointStamped > trajectory_
void addPoint(const Ogre::Vector3 &point)
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
DisplayContext * context_
virtual float getFloat() const
ros::Time getTime()
Ogre::SceneNode * scene_node_
virtual void setColor(float r, float g, float b, float a)
string str
virtual FrameManager * getFrameManager() const =0
const std::string & getFixedFrame()
void setNumLines(uint32_t num)
void setMaxPointsPerLine(uint32_t max)
virtual Ogre::SceneManager * getSceneManager() const =0
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setFrameManager(FrameManager *frame_manager)
virtual void update(float wall_dt, float ros_dt)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
void setLineWidth(float width)
QString getFrame() const


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sat Mar 20 2021 03:03:18