point_click_publisher_plugin.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #include "mapviz_plugins/point_click_publisher_plugin.h"
00031 #include <geometry_msgs/PointStamped.h>
00032 #include <swri_transform_util/frames.h>
00033 #include <swri_yaml_util/yaml_util.h>
00034 
00035 #include <boost/shared_ptr.hpp>
00036 
00037 // Declare plugin
00038 #include <pluginlib/class_list_macros.h>
00039 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::PointClickPublisherPlugin, mapviz::MapvizPlugin)
00040 
00041 namespace mapviz_plugins
00042 {
00043   PointClickPublisherPlugin::PointClickPublisherPlugin() :
00044     config_widget_(new QWidget()),
00045     canvas_(NULL)
00046   {
00047     ui_.setupUi(config_widget_);
00048 
00049     connect(&click_filter_, SIGNAL(pointClicked(const QPointF&)),
00050             this, SLOT(pointClicked(const QPointF&)));
00051     connect(ui_.topic, SIGNAL(textEdited(const QString&)),
00052             this, SLOT(topicChanged(const QString&)));
00053 
00054     frame_timer_.start(1000);
00055     connect(&frame_timer_, SIGNAL(timeout()), this, SLOT(updateFrames()));
00056   }
00057 
00058   PointClickPublisherPlugin::~PointClickPublisherPlugin()
00059   {
00060     if (canvas_)
00061     {
00062       canvas_->removeEventFilter(&click_filter_);
00063     }
00064   }
00065 
00066   bool PointClickPublisherPlugin::Initialize(QGLWidget* canvas)
00067   {
00068     canvas_ = static_cast<mapviz::MapCanvas*>(canvas);
00069     canvas_->installEventFilter(&click_filter_);
00070 
00071     PrintInfo("Ready.");
00072 
00073     return true;
00074   }
00075 
00076   void PointClickPublisherPlugin::Draw(double x, double y, double scale)
00077   {
00078   }
00079 
00080   void PointClickPublisherPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00081   {
00082     std::string tmp;
00083     if (swri_yaml_util::FindValue(node, "topic"))
00084     {
00085       node["topic"] >> tmp;
00086       ui_.topic->setText(QString(tmp.c_str()));
00087       topicChanged(ui_.topic->text());
00088     }
00089 
00090     if (swri_yaml_util::FindValue(node, "output_frame"))
00091     {
00092       node["output_frame"] >> tmp;
00093       ui_.outputframe->addItem(QString(tmp.c_str()));
00094     }
00095   }
00096 
00097   void PointClickPublisherPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00098   {
00099     emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
00100     emitter << YAML::Key << "output_frame" << YAML::Value << ui_.outputframe->currentText().toStdString();
00101   }
00102 
00103   QWidget* PointClickPublisherPlugin::GetConfigWidget(QWidget* parent)
00104   {
00105     config_widget_->setParent(parent);
00106 
00107     return config_widget_;
00108   }
00109 
00110 
00111   void PointClickPublisherPlugin::pointClicked(const QPointF& point)
00112   {
00113     QPointF transformed = canvas_->MapGlCoordToFixedFrame(point);
00114 
00115     std::string output_frame = ui_.outputframe->currentText().toStdString();
00116 
00117     if (target_frame_ != output_frame)
00118     {
00119       swri_transform_util::Transform tf;
00120       tf::Point tfPoint(transformed.x(), transformed.y(), 0.0);
00121       if (tf_manager_.GetTransform(output_frame, target_frame_, tf))
00122       {
00123         tfPoint = tf * tfPoint;
00124       }
00125       else
00126       {
00127         std::stringstream error;
00128         error << "Unable to find transform from " << target_frame_ << " to " << output_frame << ".";
00129         PrintError(error.str());
00130         return;
00131       }
00132       transformed.setX(tfPoint.x());
00133       transformed.setY(tfPoint.y());
00134     }
00135 
00136     std::stringstream ss;
00137     ss << "Point in " << output_frame.c_str() << ": " << transformed.x() << "," << transformed.y();
00138     PrintInfo(ss.str());
00139 
00140     boost::shared_ptr<geometry_msgs::PointStamped> stamped = boost::make_shared<geometry_msgs::PointStamped>();
00141     stamped->header.frame_id = output_frame;
00142     stamped->header.stamp = ros::Time::now();
00143     stamped->point.x = transformed.x();
00144     stamped->point.y = transformed.y();
00145     stamped->point.z = 0.0;
00146 
00147     point_publisher_.publish(stamped);
00148   }
00149 
00150   void PointClickPublisherPlugin::SetNode(const ros::NodeHandle& node)
00151   {
00152     mapviz::MapvizPlugin::SetNode(node);
00153 
00154     // We override this method so that we can initialize our publisher after
00155     // our node has been set, ensuring that it's in mapviz's namespace.
00156     topicChanged(ui_.topic->text());
00157   }
00158 
00159   void PointClickPublisherPlugin::PrintError(const std::string& message)
00160   {
00161     PrintErrorHelper(ui_.status, message);
00162   }
00163 
00164   void PointClickPublisherPlugin::PrintInfo(const std::string& message)
00165   {
00166     PrintInfoHelper(ui_.status, message);
00167   }
00168 
00169   void PointClickPublisherPlugin::PrintWarning(const std::string& message)
00170   {
00171     PrintWarningHelper(ui_.status, message);
00172   }
00173 
00174 
00175   void PointClickPublisherPlugin::topicChanged(const QString& topic)
00176   {
00177     std::stringstream ss;
00178     ss << "Publishing points to topic: " << topic.toStdString().c_str();
00179     PrintInfo(ss.str());
00180 
00181     if (!topic.isEmpty())
00182     {
00183       point_publisher_ = node_.advertise<geometry_msgs::PointStamped>(topic.toStdString(), 1000);
00184     }
00185   }
00186 
00187   void PointClickPublisherPlugin::updateFrames()
00188   {
00189     std::vector<std::string> frames;
00190     tf_->getFrameStrings(frames);
00191 
00192     bool supports_wgs84 = tf_manager_.SupportsTransform(
00193         swri_transform_util::_local_xy_frame,
00194         swri_transform_util::_wgs84_frame);
00195 
00196     if (supports_wgs84)
00197     {
00198       frames.push_back(swri_transform_util::_wgs84_frame);
00199     }
00200 
00201     if (ui_.outputframe->count() >= 0 &&
00202         static_cast<size_t>(ui_.outputframe->count()) == frames.size())
00203     {
00204       bool changed = false;
00205       for (size_t i = 0; i < frames.size(); i++)
00206       {
00207         if (frames[i] != ui_.outputframe->itemText(static_cast<int>(i)).toStdString())
00208         {
00209           changed = true;
00210         }
00211       }
00212 
00213       if (!changed)
00214         return;
00215     }
00216 
00217     std::string current_output = ui_.outputframe->currentText().toStdString();
00218 
00219     ui_.outputframe->clear();
00220     for (size_t i = 0; i < frames.size(); i++)
00221     {
00222       ui_.outputframe->addItem(frames[i].c_str());
00223     }
00224 
00225     if (current_output != "")
00226     {
00227       int index = ui_.outputframe->findText(current_output.c_str());
00228       if (index < 0)
00229       {
00230         ui_.outputframe->addItem(current_output.c_str());
00231       }
00232 
00233       index = ui_.outputframe->findText(current_output.c_str());
00234       ui_.outputframe->setCurrentIndex(index);
00235     }
00236   }
00237 }


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 18:51:07