Go to the documentation of this file.
   30 #ifndef MAPVIZ_PLUGINS_MARKER_PLUGIN_H_ 
   31 #define MAPVIZ_PLUGINS_MARKER_PLUGIN_H_ 
   35 #include <unordered_map> 
   41 #include <QListWidgetItem> 
   46 #include <visualization_msgs/MarkerArray.h> 
   51 #include "ui_marker_config.h" 
   60       boost::hash_combine(seed, p.first);
 
   61       boost::hash_combine(seed, p.second);
 
   69       boost::hash_combine(seed, p);
 
   85     void Draw(
double x, 
double y, 
double scale);
 
   86     void Paint(QPainter* painter, 
double x, 
double y, 
double scale);
 
   90     void LoadConfig(
const YAML::Node& node, 
const std::string& path);
 
   91     void SaveConfig(YAML::Emitter& emitter, 
const std::string& path);
 
  102     void PrintInfo(
const std::string& message);
 
  162     std::unordered_map<MarkerId, MarkerData, MarkerIdHash> 
markers_;
 
  166     void handleMarker(
const visualization_msgs::Marker &marker);
 
  173 #endif  // MAPVIZ_PLUGINS_MARKER_PLUGIN_H_ 
  
void timerEvent(QTimerEvent *)
void handleMarker(const visualization_msgs::Marker &marker)
tf::Point transformed_arrow_left
void Draw(double x, double y, double scale)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
std::unordered_map< std::string, bool, MarkerNsHash > marker_visible_
void PrintError(const std::string &message)
void handleMarkerArray(const visualization_msgs::MarkerArray &markers)
std::size_t operator()(const MarkerId &p) const
void transformArrow(MarkerData &markerData, const swri_transform_util::Transform &transform)
tf::Quaternion orientation
std::unordered_map< MarkerId, MarkerData, MarkerIdHash > markers_
tf::Point transformed_arrow_right
tf::Point transformed_point
bool Initialize(QGLWidget *canvas)
std::pair< std::string, int > MarkerId
void PrintWarning(const std::string &message)
std::size_t operator()(const std::string &p) const
void Paint(QPainter *painter, double x, double y, double scale)
void handleMessage(const topic_tools::ShapeShifter::ConstPtr &msg)
tf::Point transformed_arrow_point
std::vector< StampedPoint > points
void PrintInfo(const std::string &message)
ros::Subscriber marker_sub_
void LoadConfig(const YAML::Node &node, const std::string &path)
QWidget * GetConfigWidget(QWidget *parent)
swri_transform_util::Transform local_transform
mapviz_plugins
Author(s): Marc Alban
autogenerated on Sun Sep 8 2024 02:27:14