30 #ifndef MAPVIZ_PLUGINS_MARKER_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_MARKER_PLUGIN_H_ 50 #include <visualization_msgs/Marker.h> 51 #include <visualization_msgs/MarkerArray.h> 52 #include <std_msgs/ColorRGBA.h> 57 #include "ui_marker_config.h" 74 void Draw(
double x,
double y,
double scale);
75 void Paint(QPainter* painter,
double x,
double y,
double scale);
79 void LoadConfig(
const YAML::Node& node,
const std::string& path);
80 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
91 void PrintInfo(
const std::string& message);
145 std::map<std::string, std::map<int, MarkerData> >
markers_;
148 void handleMarker(
const visualization_msgs::Marker &marker);
155 #endif // MAPVIZ_PLUGINS_MARKER_PLUGIN_H_
tf::Point transformed_arrow_right
void handleMessage(const topic_tools::ShapeShifter::ConstPtr &msg)
std::list< StampedPoint > points
void handleMarker(const visualization_msgs::Marker &marker)
tf::Quaternion orientation
void Draw(double x, double y, double scale)
std::map< std::string, std::map< int, MarkerData > > markers_
tf::Point transformed_point
ros::Subscriber marker_sub_
void PrintError(const std::string &message)
TFSIMD_FORCE_INLINE const tfScalar & y() const
QWidget * GetConfigWidget(QWidget *parent)
void transformArrow(MarkerData &markerData, const swri_transform_util::Transform &transform)
void LoadConfig(const YAML::Node &node, const std::string &path)
tf::Point transformed_arrow_point
void PrintWarning(const std::string &message)
tf::Point transformed_arrow_left
TFSIMD_FORCE_INLINE const tfScalar & x() const
void timerEvent(QTimerEvent *)
void Paint(QPainter *painter, double x, double y, double scale)
swri_transform_util::Transform local_transform
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void handleMarkerArray(const visualization_msgs::MarkerArray &markers)
void PrintInfo(const std::string &message)
bool Initialize(QGLWidget *canvas)