30 #ifndef MAPVIZ_PLUGINS_OBJECT_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_OBJECT_PLUGIN_H_ 44 #include <marti_nav_msgs/TrackedObjectArray.h> 45 #include <marti_nav_msgs/ObstacleArray.h> 50 #include "ui_object_config.h" 65 void Draw(
double x,
double y,
double scale);
66 void Paint(QPainter* painter,
double x,
double y,
double scale);
70 void LoadConfig(
const YAML::Node& node,
const std::string& path);
71 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
84 void PrintInfo(
const std::string& message);
133 void handleTrack(
const marti_nav_msgs::TrackedObject& obj);
134 void handleObstacle(
const marti_nav_msgs::Obstacle& obj,
const std_msgs::Header& header);
138 #endif // MAPVIZ_PLUGINS_OBJECT_PLUGIN_H_
void timerEvent(QTimerEvent *)
std::vector< ObjectData > objects_
void Draw(double x, double y, double scale)
void handleMessage(const topic_tools::ShapeShifter::ConstPtr &msg)
bool Initialize(QGLWidget *canvas)
void Paint(QPainter *painter, double x, double y, double scale)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void PrintWarning(const std::string &message)
tf::Point transformed_point
QWidget * GetConfigWidget(QWidget *parent)
void SetColor(const QColor &color)
std::vector< StampedPoint > polygon
void LoadConfig(const YAML::Node &node, const std::string &path)
void handleObstacle(const marti_nav_msgs::Obstacle &obj, const std_msgs::Header &header)
void handleTrack(const marti_nav_msgs::TrackedObject &obj)
ros::Subscriber object_sub_
void PrintInfo(const std::string &message)
swri_transform_util::Transform local_transform
void PrintError(const std::string &message)