tf_frame_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/tf_frame_plugin.h>
00031 
00032 // C++ standard libraries
00033 #include <cstdio>
00034 #include <algorithm>
00035 #include <vector>
00036 
00037 // QT libraries
00038 #include <QGLWidget>
00039 #include <QPalette>
00040 
00041 // ROS libraries
00042 #include <ros/master.h>
00043 
00044 #include <mapviz/select_frame_dialog.h>
00045 
00046 // Declare plugin
00047 #include <pluginlib/class_list_macros.h>
00048 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::TfFramePlugin, mapviz::MapvizPlugin)
00049 
00050 namespace mapviz_plugins
00051 {
00052   TfFramePlugin::TfFramePlugin() : config_widget_(new QWidget())
00053   {
00054     ui_.setupUi(config_widget_);
00055 
00056     ui_.color->setColor(Qt::green);
00057 
00058     // Set background white
00059     QPalette p(config_widget_->palette());
00060     p.setColor(QPalette::Background, Qt::white);
00061     config_widget_->setPalette(p);
00062 
00063     // Set status text red
00064     QPalette p3(ui_.status->palette());
00065     p3.setColor(QPalette::Text, Qt::red);
00066     ui_.status->setPalette(p3);
00067 
00068     QObject::connect(ui_.selectframe, SIGNAL(clicked()), this,
00069                      SLOT(SelectFrame()));
00070     QObject::connect(ui_.frame, SIGNAL(editingFinished()), this,
00071                      SLOT(FrameEdited()));
00072     QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
00073                      SLOT(PositionToleranceChanged(double)));
00074     QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
00075                      SLOT(BufferSizeChanged(int)));
00076     QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
00077                      SLOT(SetDrawStyle(QString)));
00078     QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)),
00079                      this, SLOT(SetStaticArrowSizes(bool)));
00080     QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)),
00081                      this, SLOT(SetArrowSize(int)));
00082     QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
00083                      SLOT(SetColor(const QColor&)));
00084   }
00085 
00086   TfFramePlugin::~TfFramePlugin()
00087   {
00088   }
00089 
00090   void TfFramePlugin::SelectFrame()
00091   {
00092     std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_);
00093     if (!frame.empty())
00094     {
00095       ui_.frame->setText(QString::fromStdString(frame));
00096       FrameEdited();
00097     }
00098   }
00099 
00100   void TfFramePlugin::FrameEdited()
00101   {
00102     source_frame_ = ui_.frame->text().toStdString();
00103     PrintWarning("Waiting for transform.");
00104 
00105     ROS_INFO("Setting target frame to to %s", source_frame_.c_str());
00106 
00107     initialized_ = true;
00108   }
00109 
00110   void TfFramePlugin::TimerCallback(const ros::TimerEvent& event)
00111   {
00112     swri_transform_util::Transform transform;
00113     if (GetTransform(ros::Time(), transform))
00114     {
00115       StampedPoint stamped_point;
00116       stamped_point.point = transform.GetOrigin();
00117       stamped_point.orientation = transform.GetOrientation();
00118       stamped_point.source_frame = target_frame_;
00119       stamped_point.stamp = transform.GetStamp();
00120       stamped_point.transformed = false;
00121 
00122       double distance = std::sqrt(
00123           std::pow(stamped_point.point.x() - points_.back().point.x(), 2) +
00124           std::pow(stamped_point.point.y() - points_.back().point.y(), 2));
00125 
00126       if (points_.empty() || distance >= position_tolerance_)
00127       {
00128         points_.push_back(stamped_point);
00129       }
00130 
00131       if (buffer_size_ > 0)
00132       {
00133         while (static_cast<int>(points_.size()) > buffer_size_)
00134         {
00135           points_.pop_front();
00136         }
00137       }
00138 
00139       cur_point_ = stamped_point;
00140     }
00141   }
00142 
00143   void TfFramePlugin::PrintError(const std::string& message)
00144   {
00145     PrintErrorHelper(ui_.status, message);
00146   }
00147 
00148   void TfFramePlugin::PrintInfo(const std::string& message)
00149   {
00150     PrintInfoHelper(ui_.status, message);
00151   }
00152 
00153   void TfFramePlugin::PrintWarning(const std::string& message)
00154   {
00155     PrintWarningHelper(ui_.status, message);
00156   }
00157 
00158   QWidget* TfFramePlugin::GetConfigWidget(QWidget* parent)
00159   {
00160     config_widget_->setParent(parent);
00161 
00162     return config_widget_;
00163   }
00164 
00165   bool TfFramePlugin::Initialize(QGLWidget* canvas)
00166   {
00167     canvas_ = canvas;
00168 
00169     timer_ = node_.createTimer(ros::Duration(0.1),
00170                                &TfFramePlugin::TimerCallback, this);
00171 
00172     SetColor(ui_.color->color());
00173 
00174     return true;
00175   }
00176 
00177   void TfFramePlugin::Draw(double x, double y, double scale)
00178   {
00179     if (DrawPoints(scale))
00180     {
00181       PrintInfo("OK");
00182     }
00183   }
00184   void TfFramePlugin::LoadConfig(const YAML::Node& node,
00185                                  const std::string& path)
00186   {
00187     if (node["frame"])
00188     {
00189       node["frame"] >> source_frame_;
00190       ui_.frame->setText(source_frame_.c_str());
00191     }
00192 
00193     if (node["color"])
00194     {
00195       std::string color;
00196       node["color"] >> color;
00197       SetColor(QColor(color.c_str()));
00198       ui_.color->setColor(color_);
00199     }
00200 
00201     if (node["draw_style"])
00202     {
00203       std::string draw_style;
00204       node["draw_style"] >> draw_style;
00205 
00206       if (draw_style == "lines")
00207       {
00208         draw_style_ = LINES;
00209         ui_.drawstyle->setCurrentIndex(0);
00210       }
00211       else if (draw_style == "points")
00212       {
00213         draw_style_ = POINTS;
00214         ui_.drawstyle->setCurrentIndex(1);
00215       }
00216       else if (draw_style == "arrows")
00217       {
00218         draw_style_ = ARROWS;
00219         ui_.drawstyle->setCurrentIndex(2);
00220       }
00221     }
00222 
00223     if (node["position_tolerance"])
00224     {
00225       node["position_tolerance"] >> position_tolerance_;
00226       ui_.positiontolerance->setValue(position_tolerance_);
00227     }
00228 
00229     if (node["buffer_size"])
00230     {
00231       node["buffer_size"] >> buffer_size_;
00232       ui_.buffersize->setValue(buffer_size_);
00233     }
00234 
00235     if (node["static_arrow_sizes"])
00236     {
00237       bool static_arrow_sizes = node["static_arrow_sizes"].as<bool>();
00238       ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
00239       SetStaticArrowSizes(static_arrow_sizes);
00240     }
00241 
00242     if (node["arrow_size"])
00243     {
00244       ui_.arrow_size->setValue(node["arrow_size"].as<int>());
00245     }
00246 
00247     FrameEdited();
00248   }
00249 
00250   void TfFramePlugin::SaveConfig(YAML::Emitter& emitter,
00251                                  const std::string& path)
00252   {
00253     emitter << YAML::Key << "frame" << YAML::Value
00254             << ui_.frame->text().toStdString();
00255     emitter << YAML::Key << "color" << YAML::Value
00256             << ui_.color->color().name().toStdString();
00257 
00258     std::string draw_style = ui_.drawstyle->currentText().toStdString();
00259     emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
00260 
00261     emitter << YAML::Key << "position_tolerance" <<
00262                YAML::Value << position_tolerance_;
00263 
00264     emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_size_;
00265 
00266     emitter << YAML::Key << "static_arrow_sizes" << YAML::Value << ui_.static_arrow_sizes->isChecked();
00267 
00268     emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value();
00269   }
00270 }


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