00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef MAPVIZ_MAPVIZ_PLUGIN_H_
00031 #define MAPVIZ_MAPVIZ_PLUGIN_H_
00032
00033
00034 #include <string>
00035
00036 #include <boost/make_shared.hpp>
00037 #include <boost/shared_ptr.hpp>
00038
00039
00040 #include <QWidget>
00041 #include <QGLWidget>
00042 #include <QObject>
00043
00044
00045 #include <ros/ros.h>
00046 #include <tf/transform_datatypes.h>
00047 #include <swri_transform_util/transform.h>
00048 #include <swri_transform_util/transform_manager.h>
00049 #include <swri_yaml_util/yaml_util.h>
00050
00051 #include <mapviz/widgets.h>
00052
00053 #include "stopwatch.h"
00054
00055 namespace mapviz
00056 {
00057 class MapvizPlugin : public QObject
00058 {
00059 Q_OBJECT;
00060
00061 public:
00062 virtual ~MapvizPlugin() {}
00063
00064 virtual bool Initialize(
00065 boost::shared_ptr<tf::TransformListener> tf_listener,
00066 QGLWidget* canvas)
00067 {
00068 tf_ = tf_listener;
00069 tf_manager_.Initialize(tf_);
00070 return Initialize(canvas);
00071 }
00072
00073 virtual void Shutdown() = 0;
00074
00075 virtual void ClearHistory() {}
00076
00081 virtual void Draw(double x, double y, double scale) = 0;
00082
00087 virtual void Paint(QPainter* painter, double x, double y, double scale) {};
00088
00089 void SetUseLatestTransforms(bool value)
00090 {
00091 if (value != use_latest_transforms_)
00092 {
00093 use_latest_transforms_ = value;
00094 Q_EMIT UseLatestTransformsChanged(use_latest_transforms_);
00095 }
00096 }
00097
00098 void SetName(const std::string& name) { name_ = name; }
00099
00100 std::string Name() const { return name_; }
00101
00102 void SetType(const std::string& type) { type_ = type; }
00103
00104 std::string Type() const { return type_; }
00105
00106 int DrawOrder() const { return draw_order_; }
00107
00108 void SetDrawOrder(int order)
00109 {
00110 if (draw_order_ != order)
00111 {
00112 draw_order_ = order;
00113 Q_EMIT DrawOrderChanged(draw_order_);
00114 }
00115 }
00116
00117 virtual void SetNode(const ros::NodeHandle& node)
00118 {
00119 node_ = node;
00120 }
00121
00122 void DrawPlugin(double x, double y, double scale)
00123 {
00124 if (visible_ && initialized_)
00125 {
00126 meas_transform_.start();
00127 Transform();
00128 meas_transform_.stop();
00129
00130 meas_draw_.start();
00131 Draw(x, y, scale);
00132 meas_draw_.stop();
00133 }
00134 }
00135
00136 void PaintPlugin(QPainter* painter, double x, double y, double scale)
00137 {
00138 if (visible_ && initialized_)
00139 {
00140 meas_transform_.start();
00141 Transform();
00142 meas_transform_.stop();
00143
00144 meas_paint_.start();
00145 Paint(painter, x, y, scale);
00146 meas_paint_.start();
00147 }
00148 }
00149
00150 void SetTargetFrame(std::string frame_id)
00151 {
00152 if (frame_id != target_frame_)
00153 {
00154 target_frame_ = frame_id;
00155
00156 meas_transform_.start();
00157 Transform();
00158 meas_transform_.stop();
00159
00160 Q_EMIT TargetFrameChanged(target_frame_);
00161 }
00162 }
00163
00164 bool Visible() const { return visible_; }
00165
00166 void SetVisible(bool visible)
00167 {
00168 if (visible_ != visible)
00169 {
00170 visible_ = visible;
00171 Q_EMIT VisibleChanged(visible_);
00172 }
00173 }
00174
00175 bool GetTransform(const ros::Time& stamp, swri_transform_util::Transform& transform, bool use_latest_transforms = true)
00176 {
00177 if (!initialized_)
00178 return false;
00179
00180 ros::Time time = stamp;
00181
00182 if (use_latest_transforms_ && use_latest_transforms)
00183 {
00184 time = ros::Time();
00185 }
00186
00187 ros::Duration elapsed = ros::Time::now() - time;
00188
00189 if (time != ros::Time() && elapsed > tf_->getCacheLength())
00190 {
00191 return false;
00192 }
00193
00194 if (tf_manager_.GetTransform(target_frame_, source_frame_, time, transform))
00195 {
00196 return true;
00197 }
00198 else if (elapsed.toSec() < 0.1)
00199 {
00200
00201
00202 if (tf_manager_.GetTransform(target_frame_, source_frame_, ros::Time(), transform))
00203 {
00204 return true;
00205 }
00206 }
00207
00208 return false;
00209 }
00210
00211 bool GetTransform(const std::string& source, const ros::Time& stamp, swri_transform_util::Transform& transform)
00212 {
00213 if (!initialized_)
00214 return false;
00215
00216 ros::Time time = stamp;
00217
00218 if (use_latest_transforms_)
00219 {
00220 time = ros::Time();
00221 }
00222
00223 ros::Duration elapsed = ros::Time::now() - time;
00224
00225 if (time != ros::Time() && elapsed > tf_->getCacheLength())
00226 {
00227 return false;
00228 }
00229
00230 if (tf_manager_.GetTransform(target_frame_, source, time, transform))
00231 {
00232 return true;
00233 }
00234 else if (elapsed.toSec() < 0.1)
00235 {
00236
00237
00238 if (tf_manager_.GetTransform(target_frame_, source, ros::Time(), transform))
00239 {
00240 return true;
00241 }
00242 }
00243
00244 return false;
00245 }
00246
00247 virtual void Transform() = 0;
00248
00249 virtual void LoadConfig(const YAML::Node& load, const std::string& path) = 0;
00250 virtual void SaveConfig(YAML::Emitter& emitter, const std::string& path) = 0;
00251
00252 virtual QWidget* GetConfigWidget(QWidget* parent) { return NULL; }
00253
00254 virtual void PrintError(const std::string& message) = 0;
00255 virtual void PrintInfo(const std::string& message) = 0;
00256 virtual void PrintWarning(const std::string& message) = 0;
00257
00258 void SetIcon(IconWidget* icon) { icon_ = icon; }
00259
00260 void PrintMeasurements()
00261 {
00262 std::string header = type_ + " (" + name_ + ")";
00263 meas_transform_.printInfo(header + " Transform()");
00264 meas_paint_.printInfo(header + " Paint()");
00265 meas_draw_.printInfo(header + " Draw()");
00266 }
00267
00268 static void PrintErrorHelper(QLabel *status_label, const std::string& message, double throttle = 0.0);
00269 static void PrintInfoHelper(QLabel *status_label, const std::string& message, double throttle = 0.0);
00270 static void PrintWarningHelper(QLabel *status_label, const std::string& message, double throttle = 0.0);
00271
00272 public Q_SLOTS:
00273 virtual void DrawIcon() {}
00274
00279 virtual bool SupportsPainting()
00280 {
00281 return false;
00282 }
00283
00284 Q_SIGNALS:
00285 void DrawOrderChanged(int draw_order);
00286 void SizeChanged();
00287 void TargetFrameChanged(const std::string& target_frame);
00288 void UseLatestTransformsChanged(bool use_latest_transforms);
00289 void VisibleChanged(bool visible);
00290
00291
00292 protected:
00293 bool initialized_;
00294 bool visible_;
00295
00296 QGLWidget* canvas_;
00297 IconWidget* icon_;
00298
00299 ros::NodeHandle node_;
00300
00301 boost::shared_ptr<tf::TransformListener> tf_;
00302 swri_transform_util::TransformManager tf_manager_;
00303
00304 std::string target_frame_;
00305 std::string source_frame_;
00306 std::string type_;
00307 std::string name_;
00308
00309 bool use_latest_transforms_;
00310
00311 int draw_order_;
00312
00313 virtual bool Initialize(QGLWidget* canvas) = 0;
00314
00315 MapvizPlugin() :
00316 initialized_(false),
00317 visible_(true),
00318 canvas_(NULL),
00319 icon_(NULL),
00320 tf_(),
00321 target_frame_(""),
00322 source_frame_(""),
00323 use_latest_transforms_(false),
00324 draw_order_(0) {}
00325
00326 private:
00327
00328
00329 Stopwatch meas_transform_;
00330 Stopwatch meas_paint_;
00331 Stopwatch meas_draw_;
00332 };
00333 typedef boost::shared_ptr<MapvizPlugin> MapvizPluginPtr;
00334
00335
00336
00337 inline void MapvizPlugin::PrintErrorHelper(QLabel *status_label, const std::string &message,
00338 double throttle)
00339 {
00340 if (message == status_label->text().toStdString())
00341 {
00342 return;
00343 }
00344
00345 if( throttle > 0.0){
00346 ROS_ERROR_THROTTLE(throttle, "Error: %s", message.c_str());
00347 }
00348 else{
00349 ROS_ERROR("Error: %s", message.c_str());
00350 }
00351 QPalette p(status_label->palette());
00352 p.setColor(QPalette::Text, Qt::red);
00353 status_label->setPalette(p);
00354 status_label->setText(message.c_str());
00355 }
00356
00357 inline void MapvizPlugin::PrintInfoHelper(QLabel *status_label, const std::string &message,
00358 double throttle)
00359 {
00360 if (message == status_label->text().toStdString())
00361 {
00362 return;
00363 }
00364
00365 if( throttle > 0.0){
00366 ROS_INFO_THROTTLE(throttle, "%s", message.c_str());
00367 }
00368 else{
00369 ROS_INFO("%s", message.c_str());
00370 }
00371 QPalette p(status_label->palette());
00372 p.setColor(QPalette::Text, Qt::darkGreen);
00373 status_label->setPalette(p);
00374 status_label->setText(message.c_str());
00375 }
00376
00377 inline void MapvizPlugin::PrintWarningHelper(QLabel *status_label, const std::string &message,
00378 double throttle)
00379 {
00380 if (message == status_label->text().toStdString())
00381 {
00382 return;
00383 }
00384
00385 if( throttle > 0.0){
00386 ROS_WARN_THROTTLE(throttle, "%s", message.c_str());
00387 }
00388 else{
00389 ROS_WARN("%s", message.c_str());
00390 }
00391 QPalette p(status_label->palette());
00392 p.setColor(QPalette::Text, Qt::darkYellow);
00393 status_label->setPalette(p);
00394 status_label->setText(message.c_str());
00395 }
00396
00397 }
00398 #endif // MAPVIZ_MAPVIZ_PLUGIN_H_
00399