tf_frame_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
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 Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from 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 <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
31 
32 // C++ standard libraries
33 #include <cstdio>
34 #include <algorithm>
35 #include <vector>
36 
37 // QT libraries
38 #include <QGLWidget>
39 #include <QPalette>
40 
41 // ROS libraries
42 #include <ros/master.h>
43 
45 
46 // Declare plugin
49 
50 namespace mapviz_plugins
51 {
52  TfFramePlugin::TfFramePlugin() : config_widget_(new QWidget())
53  {
54  ui_.setupUi(config_widget_);
55 
56  ui_.color->setColor(Qt::green);
57 
58  // Set background white
59  QPalette p(config_widget_->palette());
60  p.setColor(QPalette::Background, Qt::white);
61  config_widget_->setPalette(p);
62 
63  // Set status text red
64  QPalette p3(ui_.status->palette());
65  p3.setColor(QPalette::Text, Qt::red);
66  ui_.status->setPalette(p3);
67 
68  QObject::connect(ui_.selectframe, SIGNAL(clicked()), this,
69  SLOT(SelectFrame()));
70  QObject::connect(ui_.frame, SIGNAL(editingFinished()), this,
71  SLOT(FrameEdited()));
72  QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
73  SLOT(PositionToleranceChanged(double)));
74  QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
75  SLOT(BufferSizeChanged(int)));
76  QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
77  SLOT(SetDrawStyle(QString)));
78  QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)),
79  this, SLOT(SetStaticArrowSizes(bool)));
80  QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)),
81  this, SLOT(SetArrowSize(int)));
82  QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
83  SLOT(SetColor(const QColor&)));
84  }
85 
87  {
88  }
89 
91  {
92  std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_);
93  if (!frame.empty())
94  {
95  ui_.frame->setText(QString::fromStdString(frame));
96  FrameEdited();
97  }
98  }
99 
101  {
102  source_frame_ = ui_.frame->text().toStdString();
103  PrintWarning("Waiting for transform.");
104 
105  ROS_INFO("Setting target frame to to %s", source_frame_.c_str());
106 
107  initialized_ = true;
108  }
109 
111  {
113  if (GetTransform(ros::Time(), transform))
114  {
115  StampedPoint stamped_point;
116  stamped_point.point = transform.GetOrigin();
117  stamped_point.orientation = transform.GetOrientation();
118  stamped_point.source_frame = target_frame_;
119  stamped_point.stamp = transform.GetStamp();
120  stamped_point.transformed = false;
121 
122  double distance = std::sqrt(
123  std::pow(stamped_point.point.x() - points_.back().point.x(), 2) +
124  std::pow(stamped_point.point.y() - points_.back().point.y(), 2));
125 
126  if (points_.empty() || distance >= position_tolerance_)
127  {
128  points_.push_back(stamped_point);
129  }
130 
131  if (buffer_size_ > 0)
132  {
133  while (static_cast<int>(points_.size()) > buffer_size_)
134  {
135  points_.pop_front();
136  }
137  }
138 
139  cur_point_ = stamped_point;
140  }
141  }
142 
143  void TfFramePlugin::PrintError(const std::string& message)
144  {
145  PrintErrorHelper(ui_.status, message);
146  }
147 
148  void TfFramePlugin::PrintInfo(const std::string& message)
149  {
150  PrintInfoHelper(ui_.status, message);
151  }
152 
153  void TfFramePlugin::PrintWarning(const std::string& message)
154  {
155  PrintWarningHelper(ui_.status, message);
156  }
157 
158  QWidget* TfFramePlugin::GetConfigWidget(QWidget* parent)
159  {
160  config_widget_->setParent(parent);
161 
162  return config_widget_;
163  }
164 
165  bool TfFramePlugin::Initialize(QGLWidget* canvas)
166  {
167  canvas_ = canvas;
168 
171 
172  SetColor(ui_.color->color());
173 
174  return true;
175  }
176 
177  void TfFramePlugin::Draw(double x, double y, double scale)
178  {
179  if (DrawPoints(scale))
180  {
181  PrintInfo("OK");
182  }
183  }
184  void TfFramePlugin::LoadConfig(const YAML::Node& node,
185  const std::string& path)
186  {
187  if (node["frame"])
188  {
189  node["frame"] >> source_frame_;
190  ui_.frame->setText(source_frame_.c_str());
191  }
192 
193  if (node["color"])
194  {
195  std::string color;
196  node["color"] >> color;
197  SetColor(QColor(color.c_str()));
198  ui_.color->setColor(color_);
199  }
200 
201  if (node["draw_style"])
202  {
203  std::string draw_style;
204  node["draw_style"] >> draw_style;
205 
206  if (draw_style == "lines")
207  {
208  draw_style_ = LINES;
209  ui_.drawstyle->setCurrentIndex(0);
210  }
211  else if (draw_style == "points")
212  {
214  ui_.drawstyle->setCurrentIndex(1);
215  }
216  else if (draw_style == "arrows")
217  {
219  ui_.drawstyle->setCurrentIndex(2);
220  }
221  }
222 
223  if (node["position_tolerance"])
224  {
225  node["position_tolerance"] >> position_tolerance_;
226  ui_.positiontolerance->setValue(position_tolerance_);
227  }
228 
229  if (node["buffer_size"])
230  {
231  node["buffer_size"] >> buffer_size_;
232  ui_.buffersize->setValue(buffer_size_);
233  }
234 
235  if (node["static_arrow_sizes"])
236  {
237  bool static_arrow_sizes = node["static_arrow_sizes"].as<bool>();
238  ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
239  SetStaticArrowSizes(static_arrow_sizes);
240  }
241 
242  if (node["arrow_size"])
243  {
244  ui_.arrow_size->setValue(node["arrow_size"].as<int>());
245  }
246 
247  FrameEdited();
248  }
249 
250  void TfFramePlugin::SaveConfig(YAML::Emitter& emitter,
251  const std::string& path)
252  {
253  emitter << YAML::Key << "frame" << YAML::Value
254  << ui_.frame->text().toStdString();
255  emitter << YAML::Key << "color" << YAML::Value
256  << ui_.color->color().name().toStdString();
257 
258  std::string draw_style = ui_.drawstyle->currentText().toStdString();
259  emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
260 
261  emitter << YAML::Key << "position_tolerance" <<
262  YAML::Value << position_tolerance_;
263 
264  emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_size_;
265 
266  emitter << YAML::Key << "static_arrow_sizes" << YAML::Value << ui_.static_arrow_sizes->isChecked();
267 
268  emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value();
269  }
270 }
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
ros::NodeHandle node_
void Draw(double x, double y, double scale)
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
virtual void PositionToleranceChanged(double value)
virtual void SetArrowSize(int arrowSize)
void PrintWarning(const std::string &message)
void PrintError(const std::string &message)
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
tf::Quaternion GetOrientation() const
QWidget * GetConfigWidget(QWidget *parent)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
std::string target_frame_
static std::string selectFrame(boost::shared_ptr< tf::TransformListener > tf_listener, QWidget *parent=0)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
tf::Vector3 GetOrigin() const
std::string source_frame_
TFSIMD_FORCE_INLINE const tfScalar & x() const
void TimerCallback(const ros::TimerEvent &event)
#define ROS_INFO(...)
void LoadConfig(const YAML::Node &node, const std::string &path)
TFSIMD_FORCE_INLINE const tfScalar & y() const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
virtual void SetColor(const QColor &color)
virtual void SetStaticArrowSizes(bool isChecked)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
boost::shared_ptr< tf::TransformListener > tf_
void PrintInfo(const std::string &message)
virtual void SetDrawStyle(QString style)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool Initialize(QGLWidget *canvas)


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 19:25:16