map.h
Go to the documentation of this file.
1 #ifndef MRPT_BRIDGE_MAP_H
2 #define MRPT_BRIDGE_MAP_H
3 
4 #include <stdint.h>
5 #include <string>
6 
7 namespace std
8 {
9 template <class T>
10 class allocator;
11 }
12 
13 namespace std_msgs
14 {
15 template <class ContainerAllocator>
16 struct Header_;
18 }
19 
20 namespace nav_msgs
21 {
22 template <class ContainerAllocator>
25 }
26 
27 #include <mrpt/version.h>
28 namespace mrpt
29 {
30 namespace maps
31 {
32 class COccupancyGridMap2D;
33 class CMultiMetricMap;
34 }
35 }
36 using mrpt::maps::COccupancyGridMap2D;
37 using mrpt::maps::CMultiMetricMap;
38 
39 #include <mrpt/version.h>
40 
41 #if MRPT_VERSION<0x199
42 namespace mrpt
43 {
44 namespace utils
45 {
46 class CConfigFile;
47 }
48 }
49 using mrpt::utils::CConfigFile;
50 #else
51 namespace mrpt
52 {
53 namespace config
54 {
55 class CConfigFile;
56 }
57 }
58 using mrpt::config::CConfigFile;
59 #endif
60 
61 namespace mrpt_bridge
62 {
70 class MapHdl
71 {
72  private:
73  static MapHdl* instance_; // singeleton instance
74 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
75  int8_t lut_cellmrpt2ros[0xFF]; // lookup table for entry convertion
76  int8_t* lut_cellmrpt2rosPtr; // pointer to the center of the lookup table
77 // neede to work with neg. indexes
78 #else
79  int8_t lut_cellmrpt2ros[0xFFFF]; // lookup table for entry convertion
80  int8_t* lut_cellmrpt2rosPtr; // pointer to the center of the lookup table
81 // neede to work with neg. indexes
82 #endif
83  int8_t lut_cellros2mrpt[0xFF]; // lookup table for entry convertion
84  int8_t* lut_cellros2mrptPtr; // pointer to the center of the lookup table
85  // neede to work with neg. indexes
86  MapHdl();
87  MapHdl(const MapHdl&);
88  ~MapHdl();
89 
90  public:
96  static MapHdl* instance();
97 
98 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
99  const int8_t cellMrpt2Ros(int i) { return lut_cellmrpt2rosPtr[i]; }
100 #else
101  const int16_t cellMrpt2Ros(int i) { return lut_cellmrpt2rosPtr[i]; }
102 #endif
103  const int8_t cellRos2Mrpt(int i) { return lut_cellros2mrptPtr[i]; }
113  static const bool loadMap(
114  CMultiMetricMap& _metric_map,
115  const CConfigFile& _config_file,
116  const std::string& _map_file = "map.simplemap",
117  const std::string& _section_name = "metricMap", bool _debug = false);
118 };
119 
126 bool convert(const nav_msgs::OccupancyGrid& src, COccupancyGridMap2D& des);
127 
135 bool convert(
136  const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& msg,
137  const std_msgs::Header& header);
145 bool convert(const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& msg);
146 
149 } // namespace mrpt_bridge
150 
151 #endif // MRPT_BRIDGE_MAP_H
the map class is implemented as singeleton use map::instance ()->ros2mrpt ...
Definition: map.h:70
bool convert(const COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg)
Definition: map.cpp:136
Definition: map.h:20
int8_t * lut_cellros2mrptPtr
Definition: map.h:84
OccupancyGrid_< std::allocator< void > > OccupancyGrid
Definition: map.h:23
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
int8_t * lut_cellmrpt2rosPtr
Definition: map.h:80
const int8_t cellRos2Mrpt(int i)
Definition: map.h:103
const std::string header
static MapHdl * instance_
Definition: map.h:73
const int16_t cellMrpt2Ros(int i)
Definition: map.h:101


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Sat Apr 28 2018 02:49:17