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


asr_next_best_view
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:49:03