33 #ifndef rqt_map_merger__MapMerger_H 34 #define rqt_map_merger__MapMerger_H 38 #include <ui_map_merger.h> 41 #include <sensor_msgs/Image.h> 42 #include <nav_msgs/OccupancyGrid.h> 45 #include <opencv2/core/core.hpp> 93 void map1Callback(nav_msgs::OccupancyGridConstPtr
const & map);
94 void map2Callback(nav_msgs::OccupancyGridConstPtr
const & map);
154 #endif // rqt_image_view__ImageView_H ros::Publisher map_2_to_use_pub_
bool eventFilter(QObject *watched, QEvent *event)
virtual void shutdownPlugin()
ros::Timer map_save_timer_
std::vector< QImage > qimages_1_
ros::Publisher map_1_to_use_pub_
void onSlider1Moved(int idx)
std::vector< cv::Mat > cv_maps_2_
std::vector< QImage > qimages_2_
std::vector< cv::Mat > cv_maps_1_
nav_msgs::OccupancyGrid og_map_1_
nav_msgs::OccupancyGrid og_map_2_
cv::Mat occupancyGridToCvMat(const nav_msgs::OccupancyGrid *map)
cv::Mat current_transform
bool use_stored_transform_
void redraw_Label_merged()
std::vector< nav_msgs::OccupancyGrid > og_maps_1_
ros::Publisher hector_command_pub_
void map2Callback(nav_msgs::OccupancyGridConstPtr const &map)
void timerCallback(const ros::TimerEvent &e)
ros::Subscriber map_2_sub_
void map1Callback(nav_msgs::OccupancyGridConstPtr const &map)
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
image_transport::Subscriber subscriber_
void onStateUseTransformChanged(int checked)
void onSlider2Moved(int idx)
ros::Subscriber map_1_sub_
void onSaveGeotiffPressed()
nav_msgs::OccupancyGrid cvMatToOccupancyGrid(const cv::Mat *im)
std::vector< nav_msgs::OccupancyGrid > og_maps_2_