#include <pose_labeler.h>
Public Member Functions | |
uint32_t | getPixelValue (boost::shared_ptr< SDL_Surface > surface, int x, int y) |
PoseLabel | getPoseLabel (geometry_msgs::PoseWithCovarianceStamped msg) |
PoseLabeler (const std::string &label_map_filename) | |
void | setMapMetaData (const nav_msgs::MapMetaDataConstPtr &mdata) |
void | setMapMetaData (nav_msgs::MapMetaData mdata) |
~PoseLabeler () | |
Private Attributes | |
boost::shared_ptr< SDL_Surface > | label_map_ |
bool | map_loaded_ |
nav_msgs::MapMetaData | map_metadata_ |
Definition at line 49 of file pose_labeler.h.
PoseLabeler::PoseLabeler | ( | const std::string & | label_map_filename | ) |
Definition at line 35 of file pose_labeler.cpp.
Definition at line 86 of file pose_labeler.cpp.
uint32_t PoseLabeler::getPixelValue | ( | boost::shared_ptr< SDL_Surface > | surface, |
int | x, | ||
int | y | ||
) |
Definition at line 48 of file pose_labeler.cpp.
PoseLabel PoseLabeler::getPoseLabel | ( | geometry_msgs::PoseWithCovarianceStamped | msg | ) |
Definition at line 107 of file pose_labeler.cpp.
void PoseLabeler::setMapMetaData | ( | const nav_msgs::MapMetaDataConstPtr & | mdata | ) |
Definition at line 93 of file pose_labeler.cpp.
void PoseLabeler::setMapMetaData | ( | nav_msgs::MapMetaData | mdata | ) |
Definition at line 100 of file pose_labeler.cpp.
boost::shared_ptr<SDL_Surface> topological_tools::PoseLabeler::label_map_ [private] |
Definition at line 64 of file pose_labeler.h.
bool topological_tools::PoseLabeler::map_loaded_ [private] |
Definition at line 66 of file pose_labeler.h.
nav_msgs::MapMetaData topological_tools::PoseLabeler::map_metadata_ [private] |
Definition at line 68 of file pose_labeler.h.