map.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
12 #include <cstdint>
13 #include <string>
14 
15 namespace std
16 {
17 template <class T>
18 class allocator;
19 }
20 
21 namespace std_msgs
22 {
23 template <class ContainerAllocator>
24 struct Header_;
26 } // namespace std_msgs
27 
28 namespace nav_msgs
29 {
30 template <class ContainerAllocator>
33 } // namespace nav_msgs
34 
35 #include <mrpt/version.h>
36 namespace mrpt
37 {
38 namespace maps
39 {
41 class CMultiMetricMap;
42 } // namespace maps
43 } // namespace mrpt
46 
47 #include <mrpt/version.h>
48 
49 #if MRPT_VERSION < 0x199
50 namespace mrpt
51 {
52 namespace utils
53 {
54 class CConfigFile;
55 }
56 } // namespace mrpt
58 #else
59 namespace mrpt
60 {
61 namespace config
62 {
63 class CConfigFile;
64 }
65 } // namespace mrpt
66 using mrpt::config::CConfigFile;
67 #endif
68 
69 namespace mrpt_bridge
70 {
78 class MapHdl
79 {
80  private:
81  static MapHdl* instance_; // singeleton instance
82 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
83  int8_t lut_cellmrpt2ros[0xFF]; // lookup table for entry convertion
84  int8_t* lut_cellmrpt2rosPtr; // pointer to the center of the lookup table
85 // neede to work with neg. indexes
86 #else
87  int8_t lut_cellmrpt2ros[0xFFFF]; // lookup table for entry convertion
88  int8_t* lut_cellmrpt2rosPtr; // pointer to the center of the lookup table
89 // neede to work with neg. indexes
90 #endif
91  int8_t lut_cellros2mrpt[0xFF]; // lookup table for entry convertion
92  int8_t* lut_cellros2mrptPtr; // pointer to the center of the lookup table
93  // neede to work with neg. indexes
94  MapHdl();
95  MapHdl(const MapHdl&);
96  ~MapHdl();
97 
98  public:
104  static MapHdl* instance();
105 
106 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
107  const int8_t cellMrpt2Ros(int i) { return lut_cellmrpt2rosPtr[i]; }
108 #else
109  const int16_t cellMrpt2Ros(int i) { return lut_cellmrpt2rosPtr[i]; }
110 #endif
111  const int8_t cellRos2Mrpt(int i) { return lut_cellros2mrptPtr[i]; }
121  static const bool loadMap(
122  CMultiMetricMap& _metric_map, const CConfigFile& _config_file,
123  const std::string& _map_file = "map.simplemap",
124  const std::string& _section_name = "metricMap", bool _debug = false);
125 };
126 
134 
142 bool convert(
144  const std_msgs::Header& header);
153 
156 } // namespace mrpt_bridge
the map class is implemented as singeleton use map::instance ()->ros2mrpt ...
Definition: map.h:78
bool convert(const COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg)
Definition: map.cpp:144
Definition: map.h:28
int8_t * lut_cellros2mrptPtr
Definition: map.h:92
GLuint src
OccupancyGrid_< std::allocator< void > > OccupancyGrid
Definition: map.h:31
nv_oem6_header_t header
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
int8_t * lut_cellmrpt2rosPtr
Definition: map.h:88
const int8_t cellRos2Mrpt(int i)
Definition: map.h:111
static MapHdl * instance_
Definition: map.h:81
const int16_t cellMrpt2Ros(int i)
Definition: map.h:109


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Fri Feb 28 2020 03:22:14