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 namespace mrpt
00040 {
00041 namespace utils
00042 {
00043 class CConfigFile;
00044 }
00045 }
00046 
00047 namespace mrpt_bridge
00048 {
00056 class MapHdl
00057 {
00058    private:
00059         static MapHdl* instance_;  // singeleton instance
00060 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
00061         int8_t lut_cellmrpt2ros[0xFF];  // lookup table for entry convertion
00062         int8_t* lut_cellmrpt2rosPtr;  // pointer to the center of the lookup table
00063 // neede to work with neg. indexes
00064 #else
00065         int8_t lut_cellmrpt2ros[0xFFFF];  // lookup table for entry convertion
00066         int8_t* lut_cellmrpt2rosPtr;  // pointer to the center of the lookup table
00067 // neede to work with neg. indexes
00068 #endif
00069         int8_t lut_cellros2mrpt[0xFF];  // lookup table for entry convertion
00070         int8_t* lut_cellros2mrptPtr;  // pointer to the center of the lookup table
00071         // neede to work with neg. indexes
00072         MapHdl();
00073         MapHdl(const MapHdl&);
00074         ~MapHdl();
00075 
00076    public:
00082         static MapHdl* instance();
00083 
00084 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
00085         const int8_t cellMrpt2Ros(int i) { return lut_cellmrpt2rosPtr[i]; }
00086 #else
00087         const int16_t cellMrpt2Ros(int i) { return lut_cellmrpt2rosPtr[i]; }
00088 #endif
00089         const int8_t cellRos2Mrpt(int i) { return lut_cellros2mrptPtr[i]; }
00099         static const bool loadMap(
00100                 CMultiMetricMap& _metric_map,
00101                 const mrpt::utils::CConfigFile& _config_file,
00102                 const std::string& _map_file = "map.simplemap",
00103                 const std::string& _section_name = "metricMap", bool _debug = false);
00104 };
00105 
00112 bool convert(const nav_msgs::OccupancyGrid& src, COccupancyGridMap2D& des);
00113 
00121 bool convert(
00122         const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& msg,
00123         const std_msgs::Header& header);
00131 bool convert(const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& msg);
00132 
00135 }  // namespace mrpt_bridge
00136 
00137 #endif  // MRPT_BRIDGE_MAP_H


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:06