Class MapvizPlugin

Inheritance Relationships

Base Type

  • public QObject

Class Documentation

class MapvizPlugin : public QObject

Public Functions

~MapvizPlugin() override = default
inline virtual bool Initialize(std::shared_ptr<tf2_ros::Buffer> tf_buffer, std::shared_ptr<tf2_ros::TransformListener> tf_listener, swri_transform_util::TransformManagerPtr tf_manager, QGLWidget *canvas)
virtual void Shutdown() = 0
inline virtual void ClearHistory()
virtual void Draw(double x, double y, double scale) = 0

Draws on the Mapviz canvas using OpenGL commands; this will be called before Paint();

inline virtual void Paint(QPainter*, double, double, double)

Draws on the Mapviz canvas using a QPainter; this is called after Draw(). You only need to implement this if you’re actually using a QPainter.

inline void SetUseLatestTransforms(bool value)
inline void SetName(const std::string &name)
inline std::string Name() const
inline void SetType(const std::string &type)
inline std::string Type() const
inline int DrawOrder() const
inline void SetDrawOrder(int order)
inline virtual void SetNode(rclcpp::Node &node)
inline void DrawPlugin(double x, double y, double scale)
inline void PaintPlugin(QPainter *painter, double x, double y, double scale)
inline void SetTargetFrame(const std::string &frame_id)
inline bool Visible() const
inline void SetVisible(bool visible)
inline bool GetTransform(const rclcpp::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms = true)
inline bool GetTransform(const std::string &source, const rclcpp::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms = true)
virtual void Transform() = 0
virtual void LoadConfig(const YAML::Node &load, const std::string &path) = 0
virtual void SaveConfig(YAML::Emitter &emitter, const std::string &path) = 0
inline virtual QWidget *GetConfigWidget(QWidget*)
virtual void PrintError(const std::string &message) = 0
virtual void PrintInfo(const std::string &message) = 0
virtual void PrintWarning(const std::string &message) = 0
inline void SetIcon(IconWidget *icon)
inline void PrintMeasurements()
inline void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle = 0.0)
inline void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle = 0.0)
inline void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle = 0.0)

Public Slots

inline virtual void DrawIcon()
inline virtual bool SupportsPainting()

Override this to return “true” if you want QPainter support for your plugin.

Signals

void DrawOrderChanged(int draw_order)
void SizeChanged()
void TargetFrameChanged(const std::string &target_frame)
void UseLatestTransformsChanged(bool use_latest_transforms)
void VisibleChanged(bool visible)

Protected Functions

virtual bool Initialize(QGLWidget *canvas) = 0
inline MapvizPlugin()

Protected Attributes

bool initialized_
bool visible_
QGLWidget *canvas_
IconWidget *icon_
std::shared_ptr<rclcpp::Node> node_
std::shared_ptr<tf2_ros::Buffer> tf_buf_
std::shared_ptr<tf2_ros::TransformListener> tf_
swri_transform_util::TransformManagerPtr tf_manager_
std::string target_frame_
std::string source_frame_
std::string type_
std::string name_
bool use_latest_transforms_
int draw_order_