MapHelper.hpp
Go to the documentation of this file.
1 
20 #pragma once
21 
22 #include <ros/ros.h>
23 #include <nav_msgs/GetMap.h>
24 #include <nav_msgs/OccupancyGrid.h>
25 #include <nav_msgs/Path.h>
26 #include <nav_msgs/GetPlan.h>
27 #include <geometry_msgs/PoseStamped.h>
28 #include <cmath>
29 #include <vector>
30 #include <boost/tuple/tuple.hpp>
32 #include <tf/transform_listener.h>
38 
39 namespace robot_model_services {
40  struct RayTracingIndex {
41  int32_t x;
42  int32_t y;
43  int8_t occupancy;
44  public:
45  static bool topologicalCompare(const RayTracingIndex &source, const RayTracingIndex &firstIndex, const RayTracingIndex &secondIndex) {
46  SimpleVector2 sourceVector(source.x, source.y);
47  SimpleVector2 firstIndexVector(firstIndex.x, firstIndex.y);
48  SimpleVector2 secondIndexVector(secondIndex.x, secondIndex.y);
49 
50  return (firstIndexVector - sourceVector).squaredNorm() < (secondIndexVector - sourceVector).squaredNorm();
51  }
52 
53  static bool equals(const RayTracingIndex &firstIndex, const RayTracingIndex &secondIndex) {
54  SimpleVector2 firstIndexVector(firstIndex.x, firstIndex.y);
55  SimpleVector2 secondIndexVector(secondIndex.x, secondIndex.y);
56  return firstIndexVector == secondIndexVector;
57  }
58  };
60  typedef std::vector<RayTracingIndex> Ray;
61 
62 
63  class MapHelper {
64  private:
66 
71  nav_msgs::OccupancyGrid mMap;
73  nav_msgs::OccupancyGrid mRaytracingMap;
74  // table to translate from values 0-255 in Costmap2D to values -1 to 100 in OccupancyGrid
75  int8_t mCostTranslationTable[256];
76  public:
77  MapHelper(const std::string &mapTopicName = "map", const std::string &getPlanServiceName = "move_base/make_plan") : mMapReceived(false), mCollisionThreshold(45) {
78  mDebugHelperPtr = DebugHelper::getInstance();
79 
80  // set cost translation table
81  mCostTranslationTable[0] = 0; // NO obstacle
82  mCostTranslationTable[253] = 99; // INSCRIBED obstacle
83  mCostTranslationTable[254] = 100; // LETHAL obstacle
84  mCostTranslationTable[255] = -1; // UNKNOWN
85 
86  for (int i = 1; i < 253; i++) {
87  mCostTranslationTable[i] = int8_t(1 + (97 * (i - 1)) / 251);
88  }
89 
90  ros::Subscriber mapSubscriber = mGlobalNodeHandle.subscribe<nav_msgs::OccupancyGrid>(mapTopicName, 1, &MapHelper::mapReceived, this);
91  while(ros::ok() && !mMapReceived) {
92  mDebugHelperPtr->write(std::stringstream() << "Waiting for map to arrive on topic '" << mapSubscriber.getTopic() << "'",
94 
95  ros::spinOnce();
96  ros::Duration(0.5).sleep();
97  }
98 
99  mDebugHelperPtr->write(std::stringstream() << "waiting for service: " << getPlanServiceName, DebugHelper::MAP);
100  ros::service::waitForService(getPlanServiceName, -1);
101  mGetPlanServiceClient = mGlobalNodeHandle.serviceClient<nav_msgs::GetPlan>(getPlanServiceName, true);
102  while(ros::ok() && !mGetPlanServiceClient.exists()) {
103  mDebugHelperPtr->write(std::stringstream() << "Waiting for planning server to start on service '"
104  << mGetPlanServiceClient.getService(), DebugHelper::MAP);
105  ros::spinOnce();
106  ros::Duration(0.5).sleep();
107  }
108  this->setCostmap();
109  this->aggregateRaytracingMap();
110  }
111 
112  virtual ~MapHelper() { }
113  private:
114  void mapReceived(nav_msgs::OccupancyGrid map) {
115  mDebugHelperPtr->write("Map received", DebugHelper::MAP);
116  mMap = map;
117  mMapReceived = true;
118  mDebugHelperPtr->write(std::stringstream() << "Map resolution: " << mMap.info.resolution, DebugHelper::MAP);
119  mDebugHelperPtr->write(std::stringstream() << "Map translation: " << this->getTranslation(), DebugHelper::MAP);
120  mDebugHelperPtr->write(std::stringstream() << "Map orientation: " << this->getOrientation().w() << ", "
121  << this->getOrientation().x() << ", "
122  << this->getOrientation().y() << ", "
123  << this->getOrientation().z(),
125  mDebugHelperPtr->write(std::stringstream() << "Map metric width: " << this->getMetricWidth(), DebugHelper::MAP);
126  mDebugHelperPtr->write(std::stringstream() << "Map metric height: " << this->getMetricHeight(), DebugHelper::MAP);
127  }
128 
129  void setCostmap() {
130  tf2_ros::Buffer buffer(ros::Duration(10));
132  costmap_2d::Costmap2DROS lcr("costmap", buffer);
133 
134  std::string name = "global_costmap";
135  costmap_2d::Costmap2DROS costmapRos(name, buffer);
136  costmapRos.start();
137  costmapRos.updateMap();
138  costmapRos.stop();
139 
140  mCostmap = *(costmapRos.getCostmap());
141 
142  // get output path
143  std::string path;
144  mGlobalNodeHandle.getParam("/nbv/mMapsImagePath", path);
145 
146  // output costmap
147  std::string costmapPath = path + "/costmap.pgm";
148  mDebugHelperPtr->write("Outputting calculated costmap to " + costmapPath,
150  mCostmap.saveMap(costmapPath);
151  }
152 
154  mDebugHelperPtr->write("Aggregating raytracing map.", DebugHelper::MAP);
155  if (mMap.info.width != mCostmap.getSizeInCellsX() || mMap.info.height != mCostmap.getSizeInCellsY()) {
156  ROS_ERROR("Cannot aggregate raytracing map. Dimensions of map and costmap do not match!");
157  mDebugHelperPtr->write(std::stringstream() << "Map size: " << mMap.info.width << "x" << mMap.info.height, DebugHelper::MAP);
158  mDebugHelperPtr->write(std::stringstream() << "Costmap size: " << mCostmap.getSizeInCellsX() << "x" << mCostmap.getSizeInCellsY(), DebugHelper::MAP);
159  assert(mMap.info.width == mCostmap.getSizeInCellsX() && mMap.info.height == mCostmap.getSizeInCellsY());
160  }
161 
162  mRaytracingMap.info = mMap.info;
163  mRaytracingMap.data.reserve(mMap.data.size());
164  for (unsigned int y = 0; y < mMap.info.height; y++) {
165  for (unsigned int x = 0; x < mMap.info.width; x++) {
166  unsigned int index = y * mMap.info.width + x;
167  int8_t mapOccupancyValue = mMap.data[index];
168  int8_t costmapOccupancyValue = mCostTranslationTable[mCostmap.getCost(x, y)];
169  int8_t aggregatedOccupancyValue = mapOccupancyValue == -1 ? -1 : costmapOccupancyValue;
170 
171  mRaytracingMap.data[index] = aggregatedOccupancyValue;
172  }
173  }
174  mDebugHelperPtr->write("Aggregation done.", DebugHelper::MAP);
175  }
176 
177  int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const SimpleVector3 &position) {
178  int32_t mapX, mapY;
179  this->worldToMapCoordinates(position, mapX, mapY);
180  return this->getOccupancyValue(map, mapX, mapY);
181  }
182 
183  int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const SimpleVector3 &position) {
184  int32_t mapX, mapY;
185  this->worldToMapCoordinates(position, mapX, mapY);
186  return this->getOccupancyValue(costmap, mapX, mapY);
187  }
188 
189  int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const int32_t &mapX, const int32_t &mapY) {
190  uint32_t width = map.info.width;
191  uint32_t height = map.info.height;
192 
193  if (mapX < 0 || mapY < 0 || mapX >= (int32_t)width || mapY >= (int32_t)height) {
194  return -1;
195  }
196 
197  return map.data[mapX + mapY * width];
198  }
199 
200  int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const int32_t &mapX, const int32_t &mapY) {
201  uint32_t width = costmap.getSizeInCellsX();
202  uint32_t height = costmap.getSizeInCellsY();
203 
204  if (mapX < 0 || mapY < 0 || mapX >= (int32_t)width || mapY >= (int32_t)height) {
205  return -1;
206  }
207 
208  unsigned char cost = costmap.getCost(mapX, mapY);
209  return mCostTranslationTable[cost];
210  }
211 
212  public:
213  int8_t getMapOccupancyValue(const SimpleVector3 &position) {
214  return this->getOccupancyValue(mMap, position);
215  }
216 
217  int8_t getMapOccupancyValue(const int32_t &mapX, const int32_t &mapY) {
218  return this->getOccupancyValue(mMap, mapX, mapY);
219  }
220 
221 
222  int8_t getCostmapOccupancyValue(const SimpleVector3 &position) {
223  return this->getOccupancyValue(mCostmap, position);
224  }
225 
226  int8_t getCostmapOccupancyValue(const int32_t &mapX, const int32_t &mapY) {
227  return this->getOccupancyValue(mCostmap, mapX, mapY);
228  }
229 
230 
232  return this->getOccupancyValue(mRaytracingMap, position);
233  }
234 
235  int8_t getRaytracingMapOccupancyValue(const int32_t &mapX, const int32_t &mapY) {
236  return this->getOccupancyValue(mRaytracingMap, mapX, mapY);
237  }
238 
239  bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint) {
240  Ray ray;
241  bool retVal = this->doRaytracing(fromPoint, toPoint, ray);
242  return retVal;
243  }
244 
245  bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint, Ray &ray) {
246  // clear ray
247  ray.clear();
248 
249  // get the discrete coordinates from world coordinates
250  int32_t fromMapX, fromMapY;
251  this->worldToMapCoordinates(fromPoint, fromMapX, fromMapY);
252 
253  int32_t toMapX, toMapY;
254  this->worldToMapCoordinates(toPoint, toMapX, toMapY);
255 
256  // calculate the distances
257  int32_t distanceX = toMapX - fromMapX;
258  int32_t distanceY = toMapY - fromMapY;
259 
260  // return the result of a zero length raytracing
261  if (distanceX == 0 && distanceY == 0) {
262  int8_t occupancyValue = this->getRaytracingMapOccupancyValue(fromMapX, fromMapY);
263  return this->isOccupancyValueAcceptable(occupancyValue);
264  }
265 
266  // get the bounds - needed to prevent non feasible results
267  int32_t minX = std::min(fromMapX, toMapX);
268  int32_t maxX = std::max(fromMapX, toMapX);
269  int32_t minY = std::min(fromMapY, toMapY);
270  int32_t maxY = std::max(fromMapY, toMapY);
271 
272  // get the resolution
273  float resolution = mRaytracingMap.info.resolution;
274 
275  // get the signum of the distance
276  int32_t signumX = distanceX < 0 ? - 1 : 1;
277  int32_t signumY = distanceY < 0 ? - 1 : 1;
278 
279  // calculate the difference between the two points
280  SimpleVector2 diff = (toPoint - fromPoint).block<2, 1>(0, 0);
281 
282  // contains the value about success of raytracing
283  bool rayTracingSucceeded = true;
284 
285  // tracing along the x-axis
286  for (int32_t offsetX = 0; offsetX <= abs(distanceX) + 1 && diff[0] != 0; offsetX += 1) {
287  double x = (fromMapX + signumX * offsetX) * resolution;
288  double t = (x - fromPoint[0]) / diff[0];
289  double y = fromPoint[1] + t * diff[1];
290 
291  RayTracingIndex idx;
292  idx.x = (int32_t) (x / resolution);
293  idx.y = (int32_t) (y / resolution);
294  idx.occupancy = this->getRaytracingMapOccupancyValue(idx.x, idx.y);
295 
296  if (idx.x < minX || idx.x > maxX || idx.y < minY || idx.y > maxY) {
297  continue;
298  }
299 
300  if (!this->isOccupancyValueAcceptable(idx.occupancy)) {
301  rayTracingSucceeded = false;
302  }
303 
304  ray.push_back(idx);
305  }
306 
307  // tracing along the y axis.
308  for (int32_t offsetY = 0; offsetY <= abs(distanceY) + 1 && diff[1] != 0; offsetY += 1) {
309  double y = (fromMapY + signumY * offsetY) * resolution;
310  double t = (y - fromPoint[1]) / diff[1];
311  double x = fromPoint[0] + t * diff[0];
312 
313  RayTracingIndex idx;
314  idx.x = (int32_t) (x / resolution);
315  idx.y = (int32_t) (y / resolution);
316  idx.occupancy = this->getRaytracingMapOccupancyValue(idx.x, idx.y);
317 
318  if (idx.x < minX || idx.x > maxX || idx.y < minY || idx.y > maxY) {
319  continue;
320  }
321 
322  if (!this->isOccupancyValueAcceptable(idx.occupancy)) {
323  rayTracingSucceeded = false;
324  }
325 
326  ray.push_back(idx);
327  }
328 
329  // do a topological sort by distance to the fromPoint
330  RayTracingIndex source = {fromMapX, fromMapY, 0};
331  std::stable_sort(ray.begin(), ray.end(), boost::bind(&RayTracingIndex::topologicalCompare, source, _1, _2));
332 
333  // remove duplicate values
334  Ray::iterator endIterator = std::unique(ray.begin(), ray.end(), &RayTracingIndex::equals);
335  ray.resize(std::distance(ray.begin(), endIterator));
336 
337  return rayTracingSucceeded;
338  }
339 
340  float getMetricWidth() {
341  return mMap.info.width * mMap.info.resolution;
342  }
343 
344  float getMetricHeight() {
345  return mMap.info.height * mMap.info.resolution;
346  }
347 
348  void worldToMapCoordinates(const SimpleVector3 &position, int32_t &x, int32_t &y) {
349  SimpleVector3 continuousMapCoords;
350  worldToMapCoordinates(position, continuousMapCoords);
351 
352  // get the map coords
353  x = (int32_t) floor(continuousMapCoords[0]);
354  y = (int32_t) floor(continuousMapCoords[1]);
355  }
356 
357  void worldToMapCoordinates(const SimpleVector3 &position, SimpleVector3 &result) {
358  SimpleVector3 translation = this->getTranslation();
359  SimpleQuaternion orientation = this->getOrientation();
360  SimpleMatrix3 rotationMatrix = orientation.toRotationMatrix();
361 
362  // the map is rotated by rotation matrix, for back transform do a transpose.
363  result = (rotationMatrix.transpose() * position - translation) / mMap.info.resolution;
364  }
365 
366  void mapToWorldCoordinates(const int32_t &x, const int32_t &y, SimpleVector3 &result) {
367  mapToWorldCoordinates(SimpleVector3(x, y, 0.0), result);
368  }
369 
370  void mapToWorldCoordinates(const SimpleVector3 &position, SimpleVector3 &result) {
371  SimpleVector3 translation = this->getTranslation();
372  SimpleQuaternion orientation = this->getOrientation();
373  result = orientation.toRotationMatrix() * position * mMap.info.resolution + translation;
374  }
375 
376  void mapToWorldSize(const double &size, double &result) {
377  result = size * mMap.info.resolution;
378  }
379 
380  void worldToMapSize(const double &size, double &result) {
381  result = size / mMap.info.resolution;
382  }
383 
385  return SimpleVector3(mMap.info.origin.position.x, mMap.info.origin.position.y, mMap.info.origin.position.z);
386  }
387 
389  return TypeHelper::getSimpleQuaternion(mMap.info.origin.orientation);
390  }
391 
392  bool isOccupancyValueAcceptable(const int8_t &occupancyValue) {
393  return occupancyValue >= 0 && occupancyValue <= mCollisionThreshold;
394  }
395 
396  void setCollisionThreshold(int8_t thresholdValue) {
397  mCollisionThreshold = thresholdValue;
398  }
399 
401  return mCollisionThreshold;
402  }
403 
404  float getSquaredDistance(const SimpleVector3 &start, const SimpleVector3 &goal) {
405  return (goal - start).squaredNorm();
406  }
407  };
408 
410 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
unsigned int getSizeInCellsX() const
std::string getTopic() const
static SimpleQuaternion getSimpleQuaternion(const geometry_msgs::Pose &pose)
Definition: TypeHelper.cpp:65
Eigen::Matrix< Precision, 2, 1 > SimpleVector2
Definition: typedef.hpp:49
void worldToMapCoordinates(const SimpleVector3 &position, SimpleVector3 &result)
Definition: MapHelper.hpp:357
costmap_2d::Costmap2D mCostmap
Definition: MapHelper.hpp:72
unsigned int getSizeInCellsY() const
float getSquaredDistance(const SimpleVector3 &start, const SimpleVector3 &goal)
Definition: MapHelper.hpp:404
int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const int32_t &mapX, const int32_t &mapY)
Definition: MapHelper.hpp:189
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool isOccupancyValueAcceptable(const int8_t &occupancyValue)
Definition: MapHelper.hpp:392
void setCollisionThreshold(int8_t thresholdValue)
Definition: MapHelper.hpp:396
static boost::shared_ptr< DebugHelper > getInstance()
Definition: DebugHelper.cpp:29
int8_t getMapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
Definition: MapHelper.hpp:217
ros::NodeHandle mGlobalNodeHandle
Definition: MapHelper.hpp:69
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void mapToWorldCoordinates(const int32_t &x, const int32_t &y, SimpleVector3 &result)
Definition: MapHelper.hpp:366
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
Definition: typedef.hpp:50
void mapToWorldCoordinates(const SimpleVector3 &position, SimpleVector3 &result)
Definition: MapHelper.hpp:370
geometry_msgs::TransformStamped t
int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const SimpleVector3 &position)
Definition: MapHelper.hpp:177
int8_t getRaytracingMapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
Definition: MapHelper.hpp:235
bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint, Ray &ray)
Definition: MapHelper.hpp:245
boost::shared_ptr< MapHelper > MapHelperPtr
Definition: MapHelper.hpp:409
ros::ServiceClient mGetPlanServiceClient
Definition: MapHelper.hpp:70
std::vector< RayTracingIndex > Ray
Definition: MapHelper.hpp:60
int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const int32_t &mapX, const int32_t &mapY)
Definition: MapHelper.hpp:200
void mapToWorldSize(const double &size, double &result)
Definition: MapHelper.hpp:376
int8_t getCostmapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
Definition: MapHelper.hpp:226
int8_t getMapOccupancyValue(const SimpleVector3 &position)
Definition: MapHelper.hpp:213
void worldToMapSize(const double &size, double &result)
Definition: MapHelper.hpp:380
bool saveMap(std::string file_name)
int8_t getRaytracingMapOccupancyValue(const SimpleVector3 &position)
Definition: MapHelper.hpp:231
bool getParam(const std::string &key, std::string &s) const
nav_msgs::OccupancyGrid mMap
Definition: MapHelper.hpp:71
int8_t getCostmapOccupancyValue(const SimpleVector3 &position)
Definition: MapHelper.hpp:222
this namespace contains all generally usable classes.
Definition: DebugHelper.hpp:27
ROSCPP_DECL bool ok()
static bool equals(const RayTracingIndex &firstIndex, const RayTracingIndex &secondIndex)
Definition: MapHelper.hpp:53
bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint)
Definition: MapHelper.hpp:239
SimpleQuaternion getOrientation()
Definition: MapHelper.hpp:388
void worldToMapCoordinates(const SimpleVector3 &position, int32_t &x, int32_t &y)
Definition: MapHelper.hpp:348
MapHelper(const std::string &mapTopicName="map", const std::string &getPlanServiceName="move_base/make_plan")
Definition: MapHelper.hpp:77
static bool topologicalCompare(const RayTracingIndex &source, const RayTracingIndex &firstIndex, const RayTracingIndex &secondIndex)
Definition: MapHelper.hpp:45
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
Eigen::Matrix< Precision, 3, 3 > SimpleMatrix3
Definition: typedef.hpp:37
boost::shared_ptr< RayTracingIndex > RayTracingIndexPtr
Definition: MapHelper.hpp:59
void mapReceived(nav_msgs::OccupancyGrid map)
Definition: MapHelper.hpp:114
std::string getService()
Costmap2D * getCostmap()
bool sleep() const
nav_msgs::OccupancyGrid mRaytracingMap
Definition: MapHelper.hpp:73
int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const SimpleVector3 &position)
Definition: MapHelper.hpp:183
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
Eigen::Quaternion< Precision > SimpleQuaternion
Definition: typedef.hpp:64
unsigned char getCost(unsigned int mx, unsigned int my) const
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)


asr_robot_model_services
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Mon Feb 28 2022 21:56:02