pose_plugin.cpp
Go to the documentation of this file.
1 
32 
33 // C++ standard libraries
34 #include <cstdio>
35 #include <vector>
36 
37 // QT libraries
38 #include <QDialog>
39 #include <QGLWidget>
40 #include <QPalette>
41 
42 #include <opencv2/core/core.hpp>
43 
44 // ROS libraries
45 #include <ros/master.h>
46 
50 
51 // Declare plugin
54 
55 namespace mapviz_plugins
56 {
57  PosePlugin::PosePlugin() : config_widget_(new QWidget())
58  {
59  ui_.setupUi(config_widget_);
60 
61  ui_.color->setColor(Qt::green);
62 
63  // Set background white
64  QPalette p(config_widget_->palette());
65  p.setColor(QPalette::Background, Qt::white);
66  config_widget_->setPalette(p);
67 
68  // Set status text red
69  QPalette p3(ui_.status->palette());
70  p3.setColor(QPalette::Text, Qt::red);
71  ui_.status->setPalette(p3);
72 
73  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this,
74  SLOT(SelectTopic()));
75  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this,
76  SLOT(TopicEdited()));
77  QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
78  SLOT(PositionToleranceChanged(double)));
79  QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
80  SLOT(BufferSizeChanged(int)));
81  QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
82  SLOT(SetDrawStyle(QString)));
83  QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)),
84  this, SLOT(SetStaticArrowSizes(bool)));
85  QObject::connect(ui_.use_latest_transforms, SIGNAL(clicked(bool)),
86  this, SLOT(SetUseLatestTransforms(bool)));
87  QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)),
88  this, SLOT(SetArrowSize(int)));
89  QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
90  SLOT(SetColor(const QColor&)));
91  QObject::connect(ui_.show_laps, SIGNAL(toggled(bool)), this,
92  SLOT(LapToggled(bool)));
93  QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this,
94  SLOT(ClearPoints()));
95  }
96 
98  {
99  }
100 
102  {
103  ros::master::TopicInfo topic =
104  mapviz::SelectTopicDialog::selectTopic("geometry_msgs/PoseStamped");
105 
106  if (!topic.name.empty())
107  {
108  ui_.topic->setText(QString::fromStdString(topic.name));
109  TopicEdited();
110  }
111  }
112 
114  {
115  std::string topic = ui_.topic->text().trimmed().toStdString();
116  if (topic != topic_)
117  {
118  initialized_ = false;
119  ClearPoints();
120  has_message_ = false;
121  PrintWarning("No messages received.");
122 
124 
125  topic_ = topic;
126  if (!topic.empty())
127  {
129 
130  ROS_INFO("Subscribing to %s", topic_.c_str());
131  }
132  }
133  }
134 
135  void PosePlugin::PoseCallback(const geometry_msgs::PoseStampedConstPtr& pose)
136  {
137  if (!has_message_)
138  {
139  initialized_ = true;
140  has_message_ = true;
141  }
142 
143  StampedPoint stamped_point;
144  stamped_point.stamp = pose->header.stamp;
145  stamped_point.source_frame = pose->header.frame_id;
146 
147  if (!points().empty() && points().back().source_frame != stamped_point.source_frame)
148  {
149  single_frame_ = false;
150  }
151 
152  stamped_point.point = tf::Point(pose->pose.position.x,
153  pose->pose.position.y,
154  pose->pose.position.z);
155 
156  stamped_point.orientation = tf::Quaternion(
157  pose->pose.orientation.x,
158  pose->pose.orientation.y,
159  pose->pose.orientation.z,
160  pose->pose.orientation.w);
161 
162  pushPoint( std::move( stamped_point) );
163  }
164 
165  void PosePlugin::PrintError(const std::string& message)
166  {
167  PrintErrorHelper(ui_.status, message);
168  }
169 
170  void PosePlugin::PrintInfo(const std::string& message)
171  {
172  PrintInfoHelper(ui_.status, message);
173  }
174 
175  void PosePlugin::PrintWarning(const std::string& message)
176  {
177  PrintWarningHelper(ui_.status, message);
178  }
179 
180  QWidget* PosePlugin::GetConfigWidget(QWidget* parent)
181  {
182  config_widget_->setParent(parent);
183 
184  return config_widget_;
185  }
186 
187  bool PosePlugin::Initialize(QGLWidget* canvas)
188  {
189  canvas_ = canvas;
190  SetColor(ui_.color->color());
191 
192  return true;
193  }
194 
195  void PosePlugin::Draw(double x, double y, double scale)
196  {
197  if (DrawPoints(scale))
198  {
199  PrintInfo("OK");
200  }
201  }
202 
203  void PosePlugin::LoadConfig(const YAML::Node& node, const std::string& path)
204  {
205  if (node["topic"])
206  {
207  std::string topic;
208  node["topic"] >> topic;
209  ui_.topic->setText(topic.c_str());
210  }
211 
212  if (node["color"])
213  {
214  std::string color;
215  node["color"] >> color;
216  QColor qcolor(color.c_str());
217  SetColor(qcolor);
218  ui_.color->setColor(qcolor);
219  }
220 
221  if (node["draw_style"])
222  {
223  std::string draw_style;
224  node["draw_style"] >> draw_style;
225 
226  if (draw_style == "lines")
227  {
228  ui_.drawstyle->setCurrentIndex(0);
229  SetDrawStyle( LINES );
230  }
231  else if (draw_style == "points")
232  {
233  ui_.drawstyle->setCurrentIndex(1);
234  SetDrawStyle( POINTS );
235  }
236  else if (draw_style == "arrows")
237  {
238  ui_.drawstyle->setCurrentIndex(2);
239  SetDrawStyle( ARROWS );
240  }
241  }
242 
243  if (node["position_tolerance"])
244  {
245  double position_tolerance;
246  node["position_tolerance"] >> position_tolerance;
247  ui_.positiontolerance->setValue(position_tolerance);
248  PositionToleranceChanged(position_tolerance);
249  }
250 
251  if (node["buffer_size"])
252  {
253  double buffer_size;
254  node["buffer_size"] >> buffer_size;
255  ui_.buffersize->setValue(buffer_size);
256  BufferSizeChanged(buffer_size);
257  }
258 
259  if (node["show_laps"])
260  {
261  bool show_laps = false;
262  node["show_laps"] >> show_laps;
263  ui_.show_laps->setChecked(show_laps);
264  LapToggled(show_laps);
265  }
266 
267  if (node["static_arrow_sizes"])
268  {
269  bool static_arrow_sizes = node["static_arrow_sizes"].as<bool>();
270  ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
271  SetStaticArrowSizes(static_arrow_sizes);
272  }
273 
274  if (node["arrow_size"])
275  {
276  int arrow_size = node["arrow_size"].as<int>();
277  ui_.arrow_size->setValue(arrow_size);
278  SetArrowSize(arrow_size);
279  }
280 
281  if (node["use_latest_transforms"])
282  {
283  bool use_latest_transforms = node["use_latest_transforms"].as<bool>();
284  ui_.use_latest_transforms->setChecked(use_latest_transforms);
285  SetUseLatestTransforms(use_latest_transforms);
286  }
287 
288  TopicEdited();
289  }
290 
291  void PosePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
292  {
293  std::string topic = ui_.topic->text().toStdString();
294  emitter << YAML::Key << "topic" << YAML::Value << topic;
295 
296  emitter << YAML::Key << "color" << YAML::Value
297  << ui_.color->color().name().toStdString();
298 
299  std::string draw_style = ui_.drawstyle->currentText().toStdString();
300  emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
301 
302  emitter << YAML::Key << "position_tolerance" <<
303  YAML::Value << positionTolerance();
304 
305  emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize();
306 
307  bool show_laps = ui_.show_laps->isChecked();
308  emitter << YAML::Key << "show_laps" << YAML::Value << show_laps;
309 
310  emitter << YAML::Key << "static_arrow_sizes" << YAML::Value << ui_.static_arrow_sizes->isChecked();
311 
312  emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value();
313 
314  emitter << YAML::Key << "use_latest_transforms" << YAML::Value << ui_.use_latest_transforms->isChecked();
315  }
316 }
mapviz_plugins::PointDrawingPlugin::StampedPoint
Definition: point_drawing_plugin.h:56
mapviz_plugins::PointDrawingPlugin::LapToggled
virtual void LapToggled(bool checked)
Definition: point_drawing_plugin.cpp:160
select_topic_dialog.h
mapviz_plugins::PointDrawingPlugin::DrawPoints
virtual bool DrawPoints(double scale)
Definition: point_drawing_plugin.cpp:258
mapviz_plugins::PointDrawingPlugin::ClearPoints
void ClearPoints()
Definition: point_drawing_plugin.cpp:218
mapviz_plugins::PosePlugin::PosePlugin
PosePlugin()
Definition: pose_plugin.cpp:57
mapviz_plugins::PointDrawingPlugin::BufferSizeChanged
virtual void BufferSizeChanged(int value)
Definition: point_drawing_plugin.cpp:245
pose_plugin.h
mapviz::MapvizPlugin::PrintErrorHelper
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PointDrawingPlugin::SetColor
virtual void SetColor(const QColor &color)
Definition: point_drawing_plugin.cpp:405
mapviz_plugins::PosePlugin::config_widget_
QWidget * config_widget_
Definition: pose_plugin.h:92
mapviz_plugins::PosePlugin::SelectTopic
void SelectTopic()
Definition: pose_plugin.cpp:101
mapviz_plugins::PosePlugin::PrintWarning
void PrintWarning(const std::string &message)
Definition: pose_plugin.cpp:175
geometry_util.h
ros::Subscriber::shutdown
void shutdown()
mapviz_plugins::PointDrawingPlugin::SetStaticArrowSizes
virtual void SetStaticArrowSizes(bool isChecked)
Definition: point_drawing_plugin.cpp:149
mapviz_plugins::PointDrawingPlugin::SetUseLatestTransforms
virtual void SetUseLatestTransforms(bool checked)
Definition: point_drawing_plugin.cpp:175
mapviz_plugins::PointDrawingPlugin::pushPoint
void pushPoint(StampedPoint point)
Definition: point_drawing_plugin.cpp:198
mapviz_plugins::PointDrawingPlugin::StampedPoint::source_frame
std::string source_frame
Definition: point_drawing_plugin.h:66
mapviz_plugins::PosePlugin::GetConfigWidget
QWidget * GetConfigWidget(QWidget *parent)
Definition: pose_plugin.cpp:180
mapviz_plugins::PointDrawingPlugin::positionTolerance
double positionTolerance() const
Definition: point_drawing_plugin.cpp:235
mapviz_plugins::PosePlugin::TopicEdited
void TopicEdited()
Definition: pose_plugin.cpp:113
class_list_macros.h
mapviz_plugins::PointDrawingPlugin::LINES
@ LINES
Definition: point_drawing_plugin.h:76
tf::Point
tf::Vector3 Point
transform_util.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mapviz_plugins::PointDrawingPlugin::PositionToleranceChanged
virtual void PositionToleranceChanged(double value)
Definition: point_drawing_plugin.cpp:155
mapviz_plugins::PosePlugin::pose_sub_
ros::Subscriber pose_sub_
Definition: pose_plugin.h:96
mapviz::MapvizPlugin::PrintWarningHelper
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PosePlugin::Draw
void Draw(double x, double y, double scale)
Definition: pose_plugin.cpp:195
mapviz_plugins::PointDrawingPlugin::bufferSize
double bufferSize() const
Definition: point_drawing_plugin.cpp:223
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
mapviz_plugins::PosePlugin
Definition: pose_plugin.h:61
mapviz_plugins::PosePlugin::PrintError
void PrintError(const std::string &message)
Definition: pose_plugin.cpp:165
mapviz_plugins::PosePlugin::SaveConfig
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
Definition: pose_plugin.cpp:291
mapviz_plugins::PointDrawingPlugin::POINTS
@ POINTS
Definition: point_drawing_plugin.h:77
mapviz::MapvizPlugin::PrintInfoHelper
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PosePlugin::Initialize
bool Initialize(QGLWidget *canvas)
Definition: pose_plugin.cpp:187
mapviz_plugins::PosePlugin::~PosePlugin
virtual ~PosePlugin()
Definition: pose_plugin.cpp:97
mapviz::MapvizPlugin::canvas_
QGLWidget * canvas_
mapviz_plugins::PointDrawingPlugin::StampedPoint::orientation
tf::Quaternion orientation
Definition: point_drawing_plugin.h:61
mapviz_plugins::PointDrawingPlugin::ARROWS
@ ARROWS
Definition: point_drawing_plugin.h:78
mapviz_plugins::PointDrawingPlugin::SetArrowSize
virtual void SetArrowSize(int arrowSize)
Definition: point_drawing_plugin.cpp:119
mapviz_plugins::PointDrawingPlugin::SetDrawStyle
virtual void SetDrawStyle(QString style)
Definition: point_drawing_plugin.cpp:125
mapviz_plugins::PosePlugin::has_message_
bool has_message_
Definition: pose_plugin.h:97
mapviz_plugins::PosePlugin::topic_
std::string topic_
Definition: pose_plugin.h:94
mapviz_plugins::PosePlugin::PoseCallback
void PoseCallback(const geometry_msgs::PoseStampedConstPtr &pose)
Definition: pose_plugin.cpp:135
mapviz_plugins::PointDrawingPlugin::StampedPoint::stamp
ros::Time stamp
Definition: point_drawing_plugin.h:68
mapviz::MapvizPlugin
mapviz::MapvizPlugin::initialized_
bool initialized_
mapviz_plugins::PosePlugin::PrintInfo
void PrintInfo(const std::string &message)
Definition: pose_plugin.cpp:170
mapviz_plugins::PosePlugin::LoadConfig
void LoadConfig(const YAML::Node &node, const std::string &path)
Definition: pose_plugin.cpp:203
mapviz_plugins::PointDrawingPlugin::single_frame_
bool single_frame_
Definition: point_drawing_plugin.h:123
ROS_INFO
#define ROS_INFO(...)
ros::master::TopicInfo
mapviz_plugins::PosePlugin::ui_
Ui::pose_config ui_
Definition: pose_plugin.h:91
mapviz_plugins::PointDrawingPlugin::StampedPoint::point
tf::Point point
Definition: point_drawing_plugin.h:60
mapviz_plugins
Definition: attitude_indicator_plugin.h:61
master.h
mapviz::MapvizPlugin::node_
ros::NodeHandle node_
tf::Quaternion
mapviz::SelectTopicDialog::selectTopic
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
ros::master::TopicInfo::name
std::string name
mapviz_plugins::PointDrawingPlugin::points
const std::deque< StampedPoint > & points() const
Definition: point_drawing_plugin.cpp:240


mapviz_plugins
Author(s): Marc Alban
autogenerated on Wed Jan 17 2024 03:27:49