30 #ifndef MAPVIZ_PLUGINS_GRID_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_GRID_PLUGIN_H_ 50 #include <nav_msgs/OccupancyGrid.h> 51 #include <map_msgs/OccupancyGridUpdate.h> 54 #include "ui_occupancy_grid_config.h" 71 void Draw(
double x,
double y,
double scale);
75 void LoadConfig(
const YAML::Node& node,
const std::string& path);
76 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
82 void PrintInfo(
const std::string& message);
97 Ui::occupancy_grid_config
ui_;
100 nav_msgs::OccupancyGridConstPtr
grid_;
119 void Callback(
const nav_msgs::OccupancyGridConstPtr& msg);
120 void CallbackUpdate(
const map_msgs::OccupancyGridUpdateConstPtr& msg);
126 #endif // MAPVIZ_PLUGINS_GRID_PLUGIN_H_
void PrintWarning(const std::string &message)
void upgradeCheckBoxToggled(bool)
virtual ~OccupancyGridPlugin()
Ui::occupancy_grid_config ui_
std::array< uchar, 256 *4 > Palette
void FrameChanged(std::string)
std::vector< uchar > color_buffer_
nav_msgs::OccupancyGridConstPtr grid_
void PrintError(const std::string &message)
swri_transform_util::Transform transform_
void colorSchemeUpdated(const QString &)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void LoadConfig(const YAML::Node &node, const std::string &path)
void Callback(const nav_msgs::OccupancyGridConstPtr &msg)
void PrintInfo(const std::string &message)
ros::Subscriber grid_sub_
QWidget * GetConfigWidget(QWidget *parent)
bool Initialize(QGLWidget *canvas)
void Draw(double x, double y, double scale)
std::vector< uchar > raw_buffer_
ros::Subscriber update_sub_
void CallbackUpdate(const map_msgs::OccupancyGridUpdateConstPtr &msg)