attitude_indicator_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 #include <GL/glut.h>
32 
33 // C++ standard libraries
34 #include <algorithm>
35 #include <cstdio>
36 #include <vector>
37 
38 // QT libraries
39 #include <QDebug>
40 #include <QDialog>
41 #include <QGLWidget>
42 
43 // ROS libraries
44 #include <ros/master.h>
45 
48 
49 // Declare plugin
51 
53 
54 namespace mapviz_plugins
55 {
56 #define IS_INSTANCE(msg, type) \
57  (msg->getDataType() == ros::message_traits::datatype<type>())
58 
59  AttitudeIndicatorPlugin::AttitudeIndicatorPlugin() :
60  config_widget_(new QWidget())
61  {
62  ui_.setupUi(config_widget_);
63 
64  // Set background white
65  QPalette p(config_widget_->palette());
66  p.setColor(QPalette::Background, Qt::white);
67  config_widget_->setPalette(p);
68  roll_ = pitch_ = yaw_ = 0;
69  topics_.push_back("nav_msgs/Odometry");
70  topics_.push_back("geometry_msgs/Pose");
71  topics_.push_back("sensor_msgs/Imu");
72  // Set status text red
73  QPalette p3(ui_.status->palette());
74  p3.setColor(QPalette::Text, Qt::red);
75  ui_.status->setPalette(p3);
76 
77  placer_.setRect(QRect(0, 0, 100, 100));
78  QObject::connect(this, SIGNAL(VisibleChanged(bool)),
79  &placer_, SLOT(setVisible(bool)));
80 
81  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
82  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
83  }
84 
86  {
87  }
88 
90  {
92  topics_);
93  if (topic.name.empty())
94  {
95  return;
96  }
97 
98  ui_.topic->setText(QString::fromStdString(topic.name));
99  TopicEdited();
100  }
101 
103  {
104  std::string topic = ui_.topic->text().trimmed().toStdString();
105  if (topic != topic_)
106  {
107  initialized_ = true;
108  PrintWarning("No messages received.");
109 
111  topic_ = topic;
112  if (!topic_.empty())
113  {
116 
117  ROS_INFO("Subscribing to %s", topic_.c_str());
118  }
119  }
120  }
121 
123  {
124  if (IS_INSTANCE(msg, nav_msgs::Odometry))
125  {
126  AttitudeCallbackOdom(msg->instantiate<nav_msgs::Odometry>());
127  }
128  else if (IS_INSTANCE(msg, sensor_msgs::Imu))
129  {
130  AttitudeCallbackImu(msg->instantiate<sensor_msgs::Imu>());
131  }
132  else if (IS_INSTANCE(msg, geometry_msgs::Pose))
133  {
134  AttitudeCallbackPose(msg->instantiate<geometry_msgs::Pose>());
135  }
136  else
137  {
138  PrintError("Unknown message type: " + msg->getDataType());
139  }
140  }
141 
142  void AttitudeIndicatorPlugin::AttitudeCallbackOdom(const nav_msgs::OdometryConstPtr& odometry)
143  {
145  odometry->pose.pose.orientation.x,
146  odometry->pose.pose.orientation.y,
147  odometry->pose.pose.orientation.z,
148  odometry->pose.pose.orientation.w);
149 
151  m.getRPY(roll_, pitch_, yaw_);
152  roll_ = roll_ * (180.0 / M_PI);
153  pitch_ = pitch_ * (180.0 / M_PI);
154  yaw_ = yaw_ * (180.0 / M_PI);
155 
156  ROS_INFO("roll %f,pitch %f, yaw %f", roll_, pitch_, yaw_);
157  canvas_->update();
158  }
159 
160  void AttitudeIndicatorPlugin::AttitudeCallbackImu(const sensor_msgs::ImuConstPtr& imu)
161  {
163  imu->orientation.x,
164  imu->orientation.y,
165  imu->orientation.z,
166  imu->orientation.w);
167 
169  m.getRPY(roll_, pitch_, yaw_);
170  roll_ = roll_ * (180.0 / M_PI);
171  pitch_ = pitch_ * (180.0 / M_PI);
172  yaw_ = yaw_ * (180.0 / M_PI);
173  ROS_INFO("roll %f,pitch %f, yaw %f", roll_, pitch_, yaw_);
174 
175  canvas_->update();
176  }
177 
178  void AttitudeIndicatorPlugin::AttitudeCallbackPose(const geometry_msgs::PoseConstPtr& pose)
179  {
181  pose->orientation.x,
182  pose->orientation.y,
183  pose->orientation.z,
184  pose->orientation.w);
185 
187  m.getRPY(roll_, pitch_, yaw_);
188  roll_ = roll_ * (180.0 / M_PI);
189  pitch_ = pitch_ * (180.0 / M_PI);
190  yaw_ = yaw_ * (180.0 / M_PI);
191 
192  ROS_INFO("roll %f,pitch %f, yaw %f", roll_, pitch_, yaw_);
193  canvas_->update();
194  }
195 
196  void AttitudeIndicatorPlugin::PrintError(const std::string& message)
197  {
198  PrintErrorHelper(ui_.status, message);
199  }
200 
201  void AttitudeIndicatorPlugin::PrintInfo(const std::string& message)
202  {
203  PrintInfoHelper(ui_.status, message);
204  }
205 
206  void AttitudeIndicatorPlugin::PrintWarning(const std::string& message)
207  {
208  PrintWarningHelper(ui_.status, message);
209  }
210 
212  {
213  config_widget_->setParent(parent);
214  return config_widget_;
215  }
216 
217  bool AttitudeIndicatorPlugin::Initialize(QGLWidget* canvas)
218  {
219  initialized_ = true;
220  canvas_ = canvas;
222  startTimer(50);
223  return true;
224  }
225 
227  {
229  }
230 
232  {
233  canvas_->update();
234  }
235 
237  {
238  GLdouble eqn[4] = {0.0, 0.0, 1.0, 0.0};
239  GLdouble eqn2[4] = {0.0, 0.0, -1.0, 0.0};
240  GLdouble eqn4[4] = {0.0, 0.0, 1.0, 0.05};
241  GLdouble eqn3[4] = {0.0, 0.0, -1.0, 0.05};
242 
243  glEnable(GL_DEPTH_TEST);
244  glDepthFunc(GL_LESS);
245 
246  glPushMatrix();
247 
248  glColor3f(0.392156863f, 0.584313725f, 0.929411765f);
249  glRotated(90.0 + pitch_, 1.0, 0.0, 0.0);
250 
251  glRotated(roll_, 0.0, 1.0, 0.0);
252  glRotated(yaw_, 0.0, 0.0, 1.0);
253  glClipPlane(GL_CLIP_PLANE1, eqn2);
254  glEnable(GL_CLIP_PLANE1);
255  glutSolidSphere(.8, 20, 16);
256  glDisable(GL_CLIP_PLANE1);
257  glPopMatrix();
258 
259  glPushMatrix();
260 
261  glLineWidth(2);
262  glColor3f(1.0f, 1.0f, 1.0f);
263  glRotated(90.0 + pitch_, 1.0, 0.0, 0.0);
264  glRotated(roll_, 0.0, 1.0, 0.0);
265  glRotated(yaw_, 0.0, 0.0, 1.0);
266  glClipPlane(GL_CLIP_PLANE3, eqn4);
267  glClipPlane(GL_CLIP_PLANE2, eqn3);
268  glEnable(GL_CLIP_PLANE2);
269  glEnable(GL_CLIP_PLANE3);
270  glutWireSphere(.801, 10, 16);
271  glDisable(GL_CLIP_PLANE2);
272  glDisable(GL_CLIP_PLANE3);
273  glPopMatrix();
274 
275  glPushMatrix();
276  glColor3f(0.62745098f, 0.321568627f, 0.176470588f);
277  glRotated(90.0 + pitch_, 1.0, 0.0, 0.0);//x
278  glRotated(roll_, 0.0, 1.0, 0.0);//y
279  glRotated(yaw_, 0.0, 0.0, 1.0);//z
280  glClipPlane(GL_CLIP_PLANE0, eqn);
281  glEnable(GL_CLIP_PLANE0);
282  glutSolidSphere(.8, 20, 16);
283  glDisable(GL_CLIP_PLANE0);
284  glPopMatrix();
285  glDisable(GL_DEPTH_TEST);
286  }
287 
288  void AttitudeIndicatorPlugin::Draw(double x, double y, double scale)
289  {
290  glPushAttrib(GL_ALL_ATTRIB_BITS);
291  glMatrixMode(GL_PROJECTION);
292  glPushMatrix();
293  glLoadIdentity();
294  glOrtho(0, canvas_->width(), canvas_->height(), 0, -1.0f, 1.0f);
295  glMatrixMode(GL_MODELVIEW);
296  glPushMatrix();
297  glLoadIdentity();
298  // Setup coordinate system so that we have a [-1,1]x[1,1] cube on
299  // the screen.
300  QRect rect = placer_.rect();
301  double s_x = rect.width() / 2.0;
302  double s_y = -rect.height() / 2.0;
303  double t_x = rect.right() - s_x;
304  double t_y = rect.top() - s_y;
305 
306  double m[16] = {
307  s_x, 0, 0, 0,
308  0, s_y, 0, 0,
309  0, 0, 1.0, 0,
310  t_x, t_y, 0, 1.0};
311  glMultMatrixd(m);
312 
313  // Placed in a separate function so that we don't forget to pop the
314  // GL state back.
315 
316  drawBackground();
317  drawBall();
318 
319  drawPanel();
320 
321  glPopMatrix();
322  glMatrixMode(GL_PROJECTION);
323  glPopMatrix();
324  glMatrixMode(GL_MODELVIEW);
325  glPopAttrib();
326  PrintInfo("OK!");
327  }
328 
330  {
331  glBegin(GL_TRIANGLES);
332  glColor4f(0.0f, 0.0f, 0.0f, 1.0f);
333 
334  glVertex2d(-1.0, -1.0);
335  glVertex2d(-1.0, 1.0);
336  glVertex2d(1.0, 1.0);
337 
338  glVertex2d(-1.0, -1.0);
339  glVertex2d(1.0, 1.0);
340  glVertex2d(1.0, -1.0);
341 
342  glEnd();
343  }
344 
346  {
347  glLineWidth(2);
348 
349  glBegin(GL_LINE_STRIP);
350  glColor4f(1.0f, 1.0f, 1.0f, 1.0f);
351 
352  glVertex2d(-0.9, 0.0);
353  glVertex2d(-0.2, 0.0);
354 
355  int divisions = 20;
356  for (int i = 1; i < divisions; i++)
357  {
358  glVertex2d(-0.2 * std::cos(M_PI * i / divisions),
359  -0.2 * std::sin(M_PI * i / divisions));
360  }
361 
362  glVertex2f(0.2, 0.0);
363  glVertex2f(0.9, 0.0);
364  glEnd();
365 
366  glBegin(GL_LINES);
367  glVertex2f(0.0, -0.2f);
368  glVertex2f(0.0, -0.9f);
369  glEnd();
370  }
371 
372  void AttitudeIndicatorPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
373  {
374  if (node["topic"])
375  {
376  std::string topic;
377  node["topic"] >> topic;
378  ui_.topic->setText(topic.c_str());
379  }
380 
381  QRect current = placer_.rect();
382  int x = current.x();
383  int y = current.y();
384  int width = current.width();
385  int height = current.height();
386 
387  if (swri_yaml_util::FindValue(node, "x"))
388  {
389  node["x"] >> x;
390  }
391 
392  if (swri_yaml_util::FindValue(node, "y"))
393  {
394  node["y"] >> y;
395  }
396 
397  if (swri_yaml_util::FindValue(node, "width"))
398  {
399  node["width"] >> width;
400  }
401 
402  if (swri_yaml_util::FindValue(node, "height"))
403  {
404  node["height"] >> height;
405  }
406 
407  QRect position(x, y, width, height);
408  placer_.setRect(position);
409 
410  TopicEdited();
411  }
412 
413  void AttitudeIndicatorPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
414  {
415  emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
416 
417  QRect position = placer_.rect();
418 
419  emitter << YAML::Key << "x" << YAML::Value << position.x();
420  emitter << YAML::Key << "y" << YAML::Value << position.y();
421  emitter << YAML::Key << "width" << YAML::Value << position.width();
422  emitter << YAML::Key << "height" << YAML::Value << position.height();
423  }
424 }
#define NULL
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void LoadConfig(const YAML::Node &node, const std::string &path)
ros::NodeHandle node_
void AttitudeCallbackImu(const sensor_msgs::ImuConstPtr &imu)
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void Draw(double x, double y, double scale)
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)
TFSIMD_FORCE_INLINE const tfScalar & y() const
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
#define IS_INSTANCE(msg, type)
bool FindValue(const YAML::Node &node, const std::string &name)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
#define ROS_INFO(...)
void handleMessage(const topic_tools::ShapeShifter::ConstPtr &msg)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void VisibleChanged(bool visible)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void AttitudeCallbackOdom(const nav_msgs::OdometryConstPtr &odometry)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void AttitudeCallbackPose(const geometry_msgs::PoseConstPtr &pose)


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