Go to the documentation of this file.00001
00027 #ifndef _POSE_LABELER_H_
00028 #define _POSE_LABELER_H_
00029
00030 #include <string>
00031
00032 #include <boost/shared_ptr.hpp>
00033
00034 #include <ros/ros.h>
00035
00036 #include <nav_msgs/MapMetaData.h>
00037 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00038
00039 #include <stdlib.h>
00040
00041 #include <SDL/SDL_image.h>
00042 #include <topological_tools/PoseLabel.h>
00043
00044
00045
00046
00047 namespace topological_tools
00048 {
00049 class PoseLabeler
00050 {
00051 public:
00052 PoseLabeler ( const std::string& label_map_filename );
00053
00054 ~PoseLabeler();
00055 PoseLabel getPoseLabel ( geometry_msgs::PoseWithCovarianceStamped msg );
00056 uint32_t getPixelValue ( boost::shared_ptr<SDL_Surface> surface, int x, int y );
00057
00058 void setMapMetaData ( const nav_msgs::MapMetaDataConstPtr& mdata );
00059
00060 void setMapMetaData ( nav_msgs::MapMetaData mdata );
00061
00062 private:
00063
00064 boost::shared_ptr<SDL_Surface> label_map_;
00065
00066 bool map_loaded_;
00067
00068 nav_msgs::MapMetaData map_metadata_;
00069 };
00070 }
00071
00072 #endif