pose_publisher_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2021, Trinity University
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 
33 // Declare plugin
36 
37 namespace mapviz_plugins
38 {
39 
41  config_widget_(new QWidget()),
42  map_canvas_(nullptr),
43  is_mouse_down_(false),
44  monitoring_action_state_(false)
45 {
46  ui_.setupUi(config_widget_);
47 
48  // Set background white
49  QPalette p(config_widget_->palette());
50  p.setColor(QPalette::Background, Qt::white);
51  config_widget_->setPalette(p);
52 
53  // Set status text green
54  ui_.status->setText("OK");
55  QPalette p3(ui_.status->palette());
56  p3.setColor(QPalette::Text, Qt::green);
57  ui_.status->setPalette(p3);
58 
59  QObject::connect(ui_.pushButtonPose, SIGNAL(toggled(bool)),
60  this, SLOT(on_pushButtonPose_toggled(bool)));
61 
62  QObject::connect(ui_.topic, SIGNAL(textEdited(const QString&)),
63  this, SLOT(topicChanged(const QString&)));
64 
66  frame_timer_.start(1000);
67  QObject::connect(&frame_timer_, SIGNAL(timeout()), this, SLOT(updateFrames()));
68 }
69 
71 {
72  if (map_canvas_)
73  {
74  map_canvas_->removeEventFilter(this);
75  }
76 }
77 
78 void PosePublisherPlugin::PrintError(const std::string& message)
79 {
80  PrintErrorHelper( ui_.status, message);
81 }
82 
83 void PosePublisherPlugin::PrintInfo(const std::string& message)
84 {
85  PrintInfoHelper( ui_.status, message);
86 }
87 
88 void PosePublisherPlugin::PrintWarning(const std::string& message)
89 {
90  PrintWarningHelper( ui_.status, message);
91 }
92 
93 QWidget* PosePublisherPlugin::GetConfigWidget(QWidget* parent)
94 {
95  config_widget_->setParent(parent);
96  return config_widget_;
97 }
98 
99 bool PosePublisherPlugin::Initialize(QGLWidget* canvas)
100 {
101  map_canvas_ = static_cast<mapviz::MapCanvas*>(canvas);
102  map_canvas_->installEventFilter(this);
103 
104  topicChanged(ui_.topic->text()); // set up the publish topic
105  initialized_ = true;
106  return true;
107 }
108 
109 bool PosePublisherPlugin::eventFilter(QObject *object, QEvent* event)
110 {
111  switch (event->type())
112  {
113  case QEvent::MouseButtonPress:
114  return handleMousePress(static_cast<QMouseEvent*>(event));
115  case QEvent::MouseButtonRelease:
116  return handleMouseRelease(static_cast<QMouseEvent*>(event));
117  case QEvent::MouseMove:
118  return handleMouseMove(static_cast<QMouseEvent*>(event));
119  default:
120  return false;
121  }
122 }
123 
125 {
126  ui_.pushButtonPose->setEnabled( true );
127 }
128 
129 
131 {
132  bool pose_checked = ui_.pushButtonPose->isChecked();
133 
134  if( !pose_checked)
135  {
136  return false;
137  }
138 
139  if (event->button() == Qt::LeftButton)
140  {
141  is_mouse_down_ = true;
142  arrow_angle_ = 0;
143 #if QT_VERSION >= 0x050000
145 #else
147 #endif
148  return true;
149  }
150  return false;
151 }
152 
153 bool PosePublisherPlugin::handleMouseMove(QMouseEvent* event)
154 {
155  if (is_mouse_down_)
156  {
157 #if QT_VERSION >= 0x050000
158  QPointF head_pos = map_canvas_->MapGlCoordToFixedFrame( event->localPos() );
159 #else
160  QPointF head_pos = map_canvas_->MapGlCoordToFixedFrame( event->posF() );
161 #endif
162  arrow_angle_ = atan2( head_pos.y() - arrow_tail_position_.y(),
163  head_pos.x() - arrow_tail_position_.x() );
164  }
165  return false;
166 }
167 
169 {
170  if( !is_mouse_down_ )
171  {
172  return false;
173  }
174 
175  is_mouse_down_ = false;
176 
177  bool pose_checked = ui_.pushButtonPose->isChecked();
178  if( !pose_checked )
179  {
180  return false;
181  }
182 
183 
184  if( pose_checked )
185  {
186  // Get angle/arrow_tail_position in fixed_frame
188  geometry_msgs::PoseWithCovarianceStamped pose;
189 
190  // Here it is in the target_frame_
191  pose.header.frame_id = target_frame_;
192  pose.header.stamp = ros::Time::now();
193  pose.pose.pose.position.x = arrow_tail_position_.x();
194  pose.pose.pose.position.y = arrow_tail_position_.y();
195  pose.pose.pose.position.z = 0.0;
196  tf::quaternionTFToMsg( quat_ff, pose.pose.pose.orientation );
197 
198  // Try to transform to output_frame
200  std::string output_frame = ui_.outputframe->currentText().toStdString();
201  if (tf_manager_->GetTransform(output_frame, target_frame_, transform))
202  {
203  pose.header.frame_id = output_frame;
204  tf::Vector3 pose_oframe = transform * tf::Vector3(pose.pose.pose.position.x,
205  pose.pose.pose.position.y, 0);
206  pose.pose.pose.position.x = pose_oframe.x();
207  pose.pose.pose.position.y = pose_oframe.y();
208  tf::Quaternion quat_oframe = transform * quat_ff;
209  tf::quaternionTFToMsg( quat_oframe, pose.pose.pose.orientation );
210  }
211  else
212  {
213  std::stringstream ss;
214  ss << "Couldn't get transform from "<< target_frame_
215  << " to frame " << output_frame;
216  PrintWarning(ss.str());
217  }
218 
219  if (pose_pub_==nullptr)
220  {
221  std::stringstream ss;
222  ss << "Attempting to publish to " << ui_.topic->text().toStdString().c_str()
223  << " but it's not set up...";
224  PrintError(ss.str());
225  }
226  pose_pub_.publish(pose);
227  std::stringstream ss;
228  ss << "Pose published to topic: " << ui_.topic->text().toStdString().c_str()
229  << " in frame " << pose.header.frame_id;
230  PrintInfo(ss.str());
231 
232  ui_.pushButtonPose->setChecked(false);
233  }
234  return true;
235 }
236 
237 
238 void PosePublisherPlugin::Draw(double x, double y, double scale)
239 {
240  std::array<QPointF, 7> arrow_points;
241  arrow_points[0] = QPointF(10, 0);
242  arrow_points[1] = QPointF(6, -2.5);
243  arrow_points[2] = QPointF(6.5, -1);
244  arrow_points[3] = QPointF(0, -1);
245  arrow_points[4] = QPointF(0, 1);
246  arrow_points[5] = QPointF(6.5, 1);
247  arrow_points[6] = QPointF(6, 2.5);
248 
249  if( is_mouse_down_ )
250  {
251  QPointF transformed_points[7];
252  for (size_t i=0; i<7; i++ )
253  {
254  tf::Vector3 point(arrow_points[i].x(), arrow_points[i].y(), 0);
255  point *= scale*10;
257  transformed_points[i] = QPointF(point.x() + arrow_tail_position_.x(),
258  point.y() + arrow_tail_position_.y() );
259  }
260  glColor3f(0.1, 0.9, 0.1);
261  glLineWidth(2);
262  glBegin(GL_TRIANGLE_FAN);
263  for (const QPointF& point: transformed_points )
264  {
265  glVertex2d(point.x(), point.y());
266  }
267  glEnd();
268 
269  glColor3f(0.0, 0.6, 0.0);
270  glBegin(GL_LINE_LOOP);
271  for (const QPointF& point: transformed_points )
272  {
273  glVertex2d(point.x(), point.y());
274  }
275  glEnd();
276  }
277 }
278 
279 
280 void PosePublisherPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
281 {
282  std::string tmp;
283  if (swri_yaml_util::FindValue(node, "topic"))
284  {
285  node["topic"] >> tmp;
286  ui_.topic->setText(QString(tmp.c_str()));
287  topicChanged(ui_.topic->text());
288  }
289 
290  if (swri_yaml_util::FindValue(node, "output_frame"))
291  {
292  node["output_frame"] >> tmp;
293  ui_.outputframe->addItem(QString(tmp.c_str()));
294  }
295 
296 }
297 
298 void PosePublisherPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
299 {
300  emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
301  emitter << YAML::Key << "output_frame" << YAML::Value << ui_.outputframe->currentText().toStdString();
302 }
303 
305 {
306  if(checked)
307  {
308  QPixmap cursor_pixmap = QPixmap(":/images/green-arrow.png");
309  QApplication::setOverrideCursor(QCursor(cursor_pixmap));
310  }
311  else
312  {
313  QApplication::restoreOverrideCursor();
314  }
315 }
316 
317 
318 
319  void PosePublisherPlugin::topicChanged(const QString& topic)
320  {
321  std::stringstream ss;
322  ss << "Publishing points to topic: " << topic.toStdString().c_str();
323  PrintInfo(ss.str());
324 
325  if (!topic.isEmpty())
326  {
327  pose_pub_ = node_.advertise<geometry_msgs::PoseWithCovarianceStamped>(topic.toStdString(), 1000);
328  }
329  }
330 
332  {
333  std::vector<std::string> frames;
334  tf_->getFrameStrings(frames);
335 
336  bool supports_wgs84 = tf_manager_->SupportsTransform(
339 
340  if (supports_wgs84)
341  {
342  frames.push_back(swri_transform_util::_wgs84_frame);
343  }
344 
345  if (ui_.outputframe->count() >= 0 &&
346  static_cast<size_t>(ui_.outputframe->count()) == frames.size())
347  {
348  bool changed = false;
349  for (size_t i = 0; i < frames.size(); i++)
350  {
351  if (frames[i] != ui_.outputframe->itemText(static_cast<int>(i)).toStdString())
352  {
353  changed = true;
354  }
355  }
356 
357  if (!changed)
358  return;
359  }
360 
361  std::string output_frame = ui_.outputframe->currentText().toStdString();
362 
363  ui_.outputframe->clear();
364  for (size_t i = 0; i < frames.size(); i++)
365  {
366  ui_.outputframe->addItem(frames[i].c_str());
367  }
368 
369  if (output_frame != "")
370  {
371  // Add output_frame to frame list if no already there.
372  int index = ui_.outputframe->findText(output_frame.c_str());
373  if (index < 0)
374  {
375  ui_.outputframe->addItem(output_frame.c_str());
376  }
377 
378  // Get index of output_frame in list
379  index = ui_.outputframe->findText(output_frame.c_str());
380  ui_.outputframe->setCurrentIndex(index);
381  }
382  // output_frame is ""
383  else // use map frame
384  {
385  PrintWarning("using map target frame as fallback");
386  int index = ui_.outputframe->findText(QString("map"));
387  ui_.outputframe->setCurrentIndex(index);
388  }
389  }
390 
391 }
mapviz::MapvizPlugin::tf_
boost::shared_ptr< tf::TransformListener > tf_
tf::createQuaternionFromYaw
static Quaternion createQuaternionFromYaw(double yaw)
swri_yaml_util::FindValue
bool FindValue(const YAML::Node &node, const std::string &name)
mapviz::MapCanvas::MapGlCoordToFixedFrame
QPointF MapGlCoordToFixedFrame(const QPointF &point)
mapviz_plugins::PosePublisherPlugin::nh_
ros::NodeHandle nh_
Definition: pose_publisher_plugin.h:102
mapviz_plugins::PosePublisherPlugin::Initialize
bool Initialize(QGLWidget *canvas)
Definition: pose_publisher_plugin.cpp:99
mapviz_plugins::PosePublisherPlugin::pose_pub_
ros::Publisher pose_pub_
Definition: pose_publisher_plugin.h:103
mapviz::MapvizPlugin::PrintErrorHelper
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PosePublisherPlugin::GetConfigWidget
QWidget * GetConfigWidget(QWidget *parent)
Definition: pose_publisher_plugin.cpp:93
mapviz_plugins::PosePublisherPlugin::LoadConfig
void LoadConfig(const YAML::Node &node, const std::string &path)
Definition: pose_publisher_plugin.cpp:280
mapviz_plugins::PosePublisherPlugin::arrow_tail_position_
QPointF arrow_tail_position_
Definition: pose_publisher_plugin.h:106
mapviz_plugins::PosePublisherPlugin::arrow_angle_
float arrow_angle_
Definition: pose_publisher_plugin.h:107
mapviz_plugins::PosePublisherPlugin::on_pushButtonPose_toggled
void on_pushButtonPose_toggled(bool checked)
Definition: pose_publisher_plugin.cpp:304
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
mapviz_plugins::PosePublisherPlugin::~PosePublisherPlugin
virtual ~PosePublisherPlugin()
Definition: pose_publisher_plugin.cpp:70
mapviz_plugins::PosePublisherPlugin::timerCallback
void timerCallback(const ros::TimerEvent &ev=ros::TimerEvent())
Definition: pose_publisher_plugin.cpp:124
mapviz_plugins::PosePublisherPlugin::PrintInfo
virtual void PrintInfo(const std::string &message) override
Definition: pose_publisher_plugin.cpp:83
class_list_macros.h
transform
void transform(marti_nav_msgs::Path &path, const swri_transform_util::Transform &transform, const std::string &target_frame)
mapviz_plugins::PosePublisherPlugin::handleMousePress
bool handleMousePress(QMouseEvent *)
Definition: pose_publisher_plugin.cpp:130
mapviz_plugins::PosePublisherPlugin::topicChanged
void topicChanged(const QString &topic)
Definition: pose_publisher_plugin.cpp:319
mapviz_plugins::PosePublisherPlugin::handleMouseMove
bool handleMouseMove(QMouseEvent *)
Definition: pose_publisher_plugin.cpp:153
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mapviz_plugins::PosePublisherPlugin::frame_timer_
QTimer frame_timer_
Definition: pose_publisher_plugin.h:110
mapviz_plugins::PosePublisherPlugin::ui_
Ui::pose_publisher_config ui_
Definition: pose_publisher_plugin.h:98
mapviz_plugins::PosePublisherPlugin::PrintError
virtual void PrintError(const std::string &message) override
Definition: pose_publisher_plugin.cpp:78
mapviz_plugins::PosePublisherPlugin::config_widget_
QWidget * config_widget_
Definition: pose_publisher_plugin.h:99
mapviz_plugins::PosePublisherPlugin::PosePublisherPlugin
PosePublisherPlugin()
Definition: pose_publisher_plugin.cpp:40
mapviz_plugins::PosePublisherPlugin::timer_
ros::Timer timer_
Definition: pose_publisher_plugin.h:109
swri_transform_util::Transform
mapviz::MapvizPlugin::PrintWarningHelper
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PosePublisherPlugin::eventFilter
virtual bool eventFilter(QObject *object, QEvent *event) override
Definition: pose_publisher_plugin.cpp:109
mapviz_plugins::PosePublisherPlugin::SaveConfig
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
Definition: pose_publisher_plugin.cpp:298
ros::TimerEvent
tf::Transform
mapviz_plugins::PosePublisherPlugin
Definition: pose_publisher_plugin.h:58
mapviz::MapvizPlugin::PrintInfoHelper
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz::MapCanvas
swri_transform_util::_wgs84_frame
static const std::string _wgs84_frame
pose_publisher_plugin.h
mapviz_plugins::PosePublisherPlugin::is_mouse_down_
bool is_mouse_down_
Definition: pose_publisher_plugin.h:105
tf::quaternionTFToMsg
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
mapviz::MapvizPlugin::target_frame_
std::string target_frame_
mapviz_plugins::PosePublisherPlugin::map_canvas_
mapviz::MapCanvas * map_canvas_
Definition: pose_publisher_plugin.h:100
mapviz::MapvizPlugin::tf_manager_
swri_transform_util::TransformManagerPtr tf_manager_
swri_transform_util::_local_xy_frame
static const std::string _local_xy_frame
mapviz_plugins::PosePublisherPlugin::handleMouseRelease
bool handleMouseRelease(QMouseEvent *)
Definition: pose_publisher_plugin.cpp:168
mapviz::MapvizPlugin
mapviz::MapvizPlugin::initialized_
bool initialized_
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
mapviz_plugins
Definition: attitude_indicator_plugin.h:61
mapviz::MapvizPlugin::node_
ros::NodeHandle node_
ros::Duration
tf::Quaternion
mapviz_plugins::PosePublisherPlugin::Draw
void Draw(double x, double y, double scale)
Definition: pose_publisher_plugin.cpp:238
mapviz_plugins::PosePublisherPlugin::updateFrames
void updateFrames()
Definition: pose_publisher_plugin.cpp:331
mapviz_plugins::PosePublisherPlugin::PrintWarning
virtual void PrintWarning(const std::string &message) override
Definition: pose_publisher_plugin.cpp:88
ros::Time::now
static Time now()


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