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 {
00009 template <class T>
00010 class allocator;
00011 }
00012 
00013 namespace std_msgs
00014 {
00015 template <class ContainerAllocator>
00016 struct Header_;
00017 typedef Header_<std::allocator<void>> Header;
00018 }
00019 
00020 namespace nav_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct OccupancyGrid_;
00024 typedef OccupancyGrid_<std::allocator<void>> OccupancyGrid;
00025 }
00026 
00027 #include <mrpt/version.h>
00028 namespace mrpt
00029 {
00030 namespace maps
00031 {
00032 class COccupancyGridMap2D;
00033 class CMultiMetricMap;
00034 }
00035 }
00036 using mrpt::maps::COccupancyGridMap2D;
00037 using mrpt::maps::CMultiMetricMap;
00038 
00039 #include <mrpt/version.h>
00040 
00041 #if MRPT_VERSION<0x199
00042 namespace mrpt
00043 {
00044 namespace utils
00045 {
00046 class CConfigFile;
00047 }
00048 }
00049 using mrpt::utils::CConfigFile;
00050 #else
00051 namespace mrpt
00052 {
00053 namespace config
00054 {
00055 class CConfigFile;
00056 }
00057 }
00058 using mrpt::config::CConfigFile;
00059 #endif
00060 
00061 namespace mrpt_bridge
00062 {
00070 class MapHdl
00071 {
00072    private:
00073         static MapHdl* instance_;  // singeleton instance
00074 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
00075         int8_t lut_cellmrpt2ros[0xFF];  // lookup table for entry convertion
00076         int8_t* lut_cellmrpt2rosPtr;  // pointer to the center of the lookup table
00077 // neede to work with neg. indexes
00078 #else
00079         int8_t lut_cellmrpt2ros[0xFFFF];  // lookup table for entry convertion
00080         int8_t* lut_cellmrpt2rosPtr;  // pointer to the center of the lookup table
00081 // neede to work with neg. indexes
00082 #endif
00083         int8_t lut_cellros2mrpt[0xFF];  // lookup table for entry convertion
00084         int8_t* lut_cellros2mrptPtr;  // pointer to the center of the lookup table
00085         // neede to work with neg. indexes
00086         MapHdl();
00087         MapHdl(const MapHdl&);
00088         ~MapHdl();
00089 
00090    public:
00096         static MapHdl* instance();
00097 
00098 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
00099         const int8_t cellMrpt2Ros(int i) { return lut_cellmrpt2rosPtr[i]; }
00100 #else
00101         const int16_t cellMrpt2Ros(int i) { return lut_cellmrpt2rosPtr[i]; }
00102 #endif
00103         const int8_t cellRos2Mrpt(int i) { return lut_cellros2mrptPtr[i]; }
00113         static const bool loadMap(
00114                 CMultiMetricMap& _metric_map,
00115                 const CConfigFile& _config_file,
00116                 const std::string& _map_file = "map.simplemap",
00117                 const std::string& _section_name = "metricMap", bool _debug = false);
00118 };
00119 
00126 bool convert(const nav_msgs::OccupancyGrid& src, COccupancyGridMap2D& des);
00127 
00135 bool convert(
00136         const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& msg,
00137         const std_msgs::Header& header);
00145 bool convert(const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& msg);
00146 
00149 }  // namespace mrpt_bridge
00150 
00151 #endif  // MRPT_BRIDGE_MAP_H


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Fri Apr 27 2018 05:10:54