30 #ifndef MAPVIZ_MAPVIZ_PLUGIN_H_ 31 #define MAPVIZ_MAPVIZ_PLUGIN_H_ 36 #include <boost/make_shared.hpp> 37 #include <boost/shared_ptr.hpp> 81 virtual void Draw(
double x,
double y,
double scale) = 0;
87 virtual void Paint(QPainter* painter,
double x,
double y,
double scale) {};
136 void PaintPlugin(QPainter* painter,
double x,
double y,
double scale)
145 Paint(painter, x, y, scale);
189 if (time !=
ros::Time() && elapsed >
tf_->getCacheLength())
198 else if (elapsed.
toSec() < 0.1)
225 if (time !=
ros::Time() && elapsed >
tf_->getCacheLength())
234 else if (elapsed.
toSec() < 0.1)
249 virtual void LoadConfig(
const YAML::Node&
load,
const std::string& path) = 0;
250 virtual void SaveConfig(YAML::Emitter& emitter,
const std::string& path) = 0;
254 virtual void PrintError(
const std::string& message) = 0;
255 virtual void PrintInfo(
const std::string& message) = 0;
256 virtual void PrintWarning(
const std::string& message) = 0;
268 static void PrintErrorHelper(QLabel *status_label,
const std::string& message,
double throttle = 0.0);
269 static void PrintInfoHelper(QLabel *status_label,
const std::string& message,
double throttle = 0.0);
270 static void PrintWarningHelper(QLabel *status_label,
const std::string& message,
double throttle = 0.0);
313 virtual bool Initialize(QGLWidget* canvas) = 0;
323 use_latest_transforms_(false),
340 if (message == status_label->text().toStdString())
351 QPalette p(status_label->palette());
352 p.setColor(QPalette::Text, Qt::red);
353 status_label->setPalette(p);
354 status_label->setText(message.c_str());
360 if (message == status_label->text().toStdString())
371 QPalette p(status_label->palette());
372 p.setColor(QPalette::Text, Qt::darkGreen);
373 status_label->setPalette(p);
374 status_label->setText(message.c_str());
380 if (message == status_label->text().toStdString())
391 QPalette p(status_label->palette());
392 p.setColor(QPalette::Text, Qt::darkYellow);
393 status_label->setPalette(p);
394 status_label->setText(message.c_str());
398 #endif // MAPVIZ_MAPVIZ_PLUGIN_H_ virtual void Shutdown()=0
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
void SetTargetFrame(std::string frame_id)
virtual bool SupportsPainting()
virtual void PrintWarning(const std::string &message)=0
virtual void SetNode(const ros::NodeHandle &node)
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)
void SetName(const std::string &name)
void SetVisible(bool visible)
void PaintPlugin(QPainter *painter, double x, double y, double scale)
std::string target_frame_
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
Stopwatch meas_transform_
void printInfo(const std::string &name) const
bool GetTransform(const std::string &source, const ros::Time &stamp, swri_transform_util::Transform &transform)
std::string source_frame_
void SetType(const std::string &type)
#define ROS_INFO_THROTTLE(period,...)
virtual void PrintInfo(const std::string &message)=0
#define ROS_WARN_THROTTLE(period,...)
virtual void Paint(QPainter *painter, double x, double y, double scale)
#define ROS_ERROR_THROTTLE(period,...)
virtual bool Initialize(boost::shared_ptr< tf::TransformListener > tf_listener, swri_transform_util::TransformManagerPtr tf_manager, QGLWidget *canvas)
void TargetFrameChanged(const std::string &target_frame)
void DrawPlugin(double x, double y, double scale)
boost::shared_ptr< MapvizPlugin > MapvizPluginPtr
void SetIcon(IconWidget *icon)
virtual void ClearHistory()
void SetUseLatestTransforms(bool value)
void UseLatestTransformsChanged(bool use_latest_transforms)
virtual void Draw(double x, double y, double scale)=0
void VisibleChanged(bool visible)
virtual void LoadConfig(const YAML::Node &load, const std::string &path)=0
void SetDrawOrder(int order)
boost::shared_ptr< tf::TransformListener > tf_
swri_transform_util::TransformManagerPtr tf_manager_
void DrawOrderChanged(int draw_order)
virtual QWidget * GetConfigWidget(QWidget *parent)
virtual void SaveConfig(YAML::Emitter &emitter, const std::string &path)=0
virtual void PrintError(const std::string &message)=0
bool use_latest_transforms_
virtual void Transform()=0