map.h
Go to the documentation of this file.
00001 #ifndef MRPT_BRIDGE_MAP_H
00002 #define MRPT_BRIDGE_MAP_H
00003 
00004 #include <stdint.h>
00005 #include <string>
00006 
00007 namespace std{
00008     template <class T> class allocator;
00009 }
00010 
00011 namespace std_msgs{
00012     template <class ContainerAllocator> struct Header_;
00013     typedef Header_<std::allocator<void> > Header;
00014 }
00015 
00016 namespace nav_msgs{
00017     template <class ContainerAllocator> struct OccupancyGrid_;
00018     typedef OccupancyGrid_<std::allocator<void> > OccupancyGrid;
00019 }
00020 
00021 
00022 namespace mrpt
00023 {
00024 namespace slam
00025 {
00026 class COccupancyGridMap2D;
00027 class CMultiMetricMap;
00028 }
00029 namespace utils {
00030 class CConfigFile;
00031 }
00032 }
00033 
00034 namespace mrpt_bridge
00035 {
00036 
00040 class MapHdl
00041 {
00042 private:
00043     static MapHdl* instance_; // singeleton instance
00044 #ifdef  OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
00045     int8_t lut_cellmrpt2ros[0xFF]; // lookup table for entry convertion
00046     int8_t *lut_cellmrpt2rosPtr;   // pointer to the center of the lookup table neede to work with neg. indexes
00047 #else
00048     int8_t lut_cellmrpt2ros[0xFFFF]; // lookup table for entry convertion
00049     int8_t *lut_cellmrpt2rosPtr; // pointer to the center of the lookup table neede to work with neg. indexes
00050 #endif
00051     int8_t lut_cellros2mrpt[0xFF]; // lookup table for entry convertion
00052     int8_t *lut_cellros2mrptPtr;   // pointer to the center of the lookup table neede to work with neg. indexes
00053     MapHdl ( );
00054     MapHdl ( const MapHdl& );
00055     ~MapHdl ();
00056 public:
00061     static MapHdl* instance ();
00062 
00063 #ifdef  OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
00064     const int8_t cellMrpt2Ros(int i){
00065         return lut_cellmrpt2rosPtr[i];
00066     }
00067 #else
00068     const int16_t cellMrpt2Ros(int i){
00069         return lut_cellmrpt2rosPtr[i];
00070     }
00071 #endif
00072     const int8_t cellRos2Mrpt(int i){
00073         return lut_cellros2mrptPtr[i];
00074     }
00084     static const bool loadMap(mrpt::slam::CMultiMetricMap &_metric_map, const mrpt::utils::CConfigFile &_config_file, const std::string &_map_file="map.simplemap", const std::string &_section_name="metricMap", bool _debug = false);
00085 
00086 };
00087 
00094 bool convert ( const nav_msgs::OccupancyGrid  &src, mrpt::slam::COccupancyGridMap2D  &des );
00095 
00103 bool convert (
00104     const mrpt::slam::COccupancyGridMap2D &src,
00105     nav_msgs::OccupancyGrid &msg,
00106     const std_msgs::Header &header);
00114 bool convert (
00115     const mrpt::slam::COccupancyGridMap2D &src,
00116     nav_msgs::OccupancyGrid &msg);
00117 
00118 
00119 
00120 }; //namespace mrpt_bridge
00121 
00122 #endif //MRPT_BRIDGE_MAP_H


mrpt_bridge
Author(s):
autogenerated on Mon Aug 11 2014 11:23:21