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() {
142  std::string name = "global_costmap";
143  costmap_2d::Costmap2DROS costmapRos(name, tf);
144  costmapRos.start();
145  costmapRos.updateMap();
146  costmapRos.stop();
147 
148  mCostmap = *(costmapRos.getCostmap());
149 
150  // get output path
151  std::string path;
152  mGlobalNodeHandle.getParam("/nbv/mMapsImagePath", path);
153 
154  // output costmap
155  std::string costmapPath = path + "/costmap.pgm";
156  mDebugHelperPtr->write("Outputting calculated costmap to " + costmapPath,
158  mCostmap.saveMap(costmapPath);
159  }
160 
161  /* Transform the costmap to next_best_view parameters.
162  *
163  */
165  mDebugHelperPtr->write("Aggregating raytracing map.", DebugHelper::MAP);
166  if (mMap.info.width != mCostmap.getSizeInCellsX() || mMap.info.height != mCostmap.getSizeInCellsY()) {
167  ROS_ERROR("Cannot aggregate raytracing map. Dimensions of map and costmap do not match!");
168  mDebugHelperPtr->write(std::stringstream() << "Map size: " << mMap.info.width << "x" << mMap.info.height, DebugHelper::MAP);
169  mDebugHelperPtr->write(std::stringstream() << "Costmap size: " << mCostmap.getSizeInCellsX() << "x" << mCostmap.getSizeInCellsY(), DebugHelper::MAP);
170  assert(mMap.info.width == mCostmap.getSizeInCellsX() && mMap.info.height == mCostmap.getSizeInCellsY());
171  }
172 
173  mRaytracingMap.info = mMap.info;
174  mRaytracingMap.data.reserve(mMap.data.size());
175  for (unsigned int y = 0; y < mMap.info.height; y++) {
176  for (unsigned int x = 0; x < mMap.info.width; x++) {
177  unsigned int index = y * mMap.info.width + x;
178  int8_t mapOccupancyValue = mMap.data[index];
179  int8_t costmapOccupancyValue = mCostTranslationTable[mCostmap.getCost(x, y)];
180  int8_t aggregatedOccupancyValue = mapOccupancyValue == -1 ? -1 : costmapOccupancyValue;
181 
182  mRaytracingMap.data[index] = aggregatedOccupancyValue;
183  }
184  }
185  mDebugHelperPtr->write("Aggregation done.", DebugHelper::MAP);
186  }
187 
188  int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const SimpleVector3 &position) {
189  int32_t mapX, mapY;
190  this->worldToMapCoordinates(position, mapX, mapY);
191  return this->getOccupancyValue(map, mapX, mapY);
192  }
193 
194  int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const SimpleVector3 &position) {
195  int32_t mapX, mapY;
196  this->worldToMapCoordinates(position, mapX, mapY);
197  return this->getOccupancyValue(costmap, mapX, mapY);
198  }
199 
200  int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const int32_t &mapX, const int32_t &mapY) {
201  uint32_t width = map.info.width;
202  uint32_t height = map.info.height;
203 
204  if (mapX < 0 || mapY < 0 || mapX >= (int32_t)width || mapY >= (int32_t)height) {
205  return -1;
206  }
207 
208  return map.data[mapX + mapY * width];
209  }
210 
211  int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const int32_t &mapX, const int32_t &mapY) {
212  uint32_t width = costmap.getSizeInCellsX();
213  uint32_t height = costmap.getSizeInCellsY();
214 
215  if (mapX < 0 || mapY < 0 || mapX >= (int32_t)width || mapY >= (int32_t)height) {
216  return -1;
217  }
218 
219  unsigned char cost = costmap.getCost(mapX, mapY);
220  return mCostTranslationTable[cost];
221  }
222 
223  public:
224  // 4 combinations: (occupancyGrid, costMap) x (Vector3, mapPosition)
225  int8_t getMapOccupancyValue(const SimpleVector3 &position) {
226  return this->getOccupancyValue(mMap, position);
227  }
228 
229  int8_t getMapOccupancyValue(const int32_t &mapX, const int32_t &mapY) {
230  return this->getOccupancyValue(mMap, mapX, mapY);
231  }
232 
233 
234  int8_t getCostmapOccupancyValue(const SimpleVector3 &position) {
235  return this->getOccupancyValue(mCostmap, position);
236  }
237 
238  int8_t getCostmapOccupancyValue(const int32_t &mapX, const int32_t &mapY) {
239  return this->getOccupancyValue(mCostmap, mapX, mapY);
240  }
241 
242 
244  return this->getOccupancyValue(mRaytracingMap, position);
245  }
246 
247  int8_t getRaytracingMapOccupancyValue(const int32_t &mapX, const int32_t &mapY) {
248  return this->getOccupancyValue(mRaytracingMap, mapX, mapY);
249  }
250 
251  bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint) {
252  Ray ray;
253  bool retVal = this->doRaytracing(fromPoint, toPoint, ray);
254  return retVal;
255  }
256 
257  /* Calculates the raytrace between to points and save them in ray array.
258  *
259  */
260  bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint, Ray &ray) {
261  // clear ray
262  ray.clear();
263 
264  // get the discrete coordinates from world coordinates
265  int32_t fromMapX, fromMapY;
266  this->worldToMapCoordinates(fromPoint, fromMapX, fromMapY);
267 
268  int32_t toMapX, toMapY;
269  this->worldToMapCoordinates(toPoint, toMapX, toMapY);
270 
271  // calculate the distances
272  int32_t distanceX = toMapX - fromMapX;
273  int32_t distanceY = toMapY - fromMapY;
274 
275  // return the result of a zero length raytracing
276  if (distanceX == 0 && distanceY == 0) {
277  int8_t occupancyValue = this->getRaytracingMapOccupancyValue(fromMapX, fromMapY);
278  return this->isOccupancyValueAcceptable(occupancyValue);
279  }
280 
281  // get the bounds - needed to prevent non feasible results
282  int32_t minX = std::min(fromMapX, toMapX);
283  int32_t maxX = std::max(fromMapX, toMapX);
284  int32_t minY = std::min(fromMapY, toMapY);
285  int32_t maxY = std::max(fromMapY, toMapY);
286 
287  // get the resolution
288  float resolution = mRaytracingMap.info.resolution;
289 
290  // get the signum of the distance
291  int32_t signumX = distanceX < 0 ? - 1 : 1;
292  int32_t signumY = distanceY < 0 ? - 1 : 1;
293 
294  // calculate the difference between the two points
295  SimpleVector2 diff = (toPoint - fromPoint).block<2, 1>(0, 0);
296 
297  // contains the value about success of raytracing
298  bool rayTracingSucceeded = true;
299 
300  // tracing along the x-axis
301  for (int32_t offsetX = 0; offsetX <= std::abs(distanceX) + 1 && diff[0] != 0; offsetX += 1) {
302  double x = (fromMapX + signumX * offsetX) * resolution;
303  double t = (x - fromPoint[0]) / diff[0];
304  double y = fromPoint[1] + t * diff[1];
305 
306  RayTracingIndex idx;
307  idx.x = (int32_t) (x / resolution);
308  idx.y = (int32_t) (y / resolution);
309  idx.occupancy = this->getRaytracingMapOccupancyValue(idx.x, idx.y);
310 
311  if (idx.x < minX || idx.x > maxX || idx.y < minY || idx.y > maxY) {
312  continue;
313  }
314 
315  if (!this->isOccupancyValueAcceptable(idx.occupancy)) {
316  rayTracingSucceeded = false;
317  }
318 
319  ray.push_back(idx);
320  }
321 
322  // tracing along the y axis.
323  for (int32_t offsetY = 0; offsetY <= std::abs(distanceY) + 1 && diff[1] != 0; offsetY += 1) {
324  double y = (fromMapY + signumY * offsetY) * resolution;
325  double t = (y - fromPoint[1]) / diff[1];
326  double x = fromPoint[0] + t * diff[0];
327 
328  RayTracingIndex idx;
329  idx.x = (int32_t) (x / resolution);
330  idx.y = (int32_t) (y / resolution);
331  idx.occupancy = this->getRaytracingMapOccupancyValue(idx.x, idx.y);
332 
333  if (idx.x < minX || idx.x > maxX || idx.y < minY || idx.y > maxY) {
334  continue;
335  }
336 
337  if (!this->isOccupancyValueAcceptable(idx.occupancy)) {
338  rayTracingSucceeded = false;
339  }
340 
341  ray.push_back(idx);
342  }
343 
344  // do a topological sort by distance to the fromPoint
345  RayTracingIndex source = {fromMapX, fromMapY, 0};
346  std::stable_sort(ray.begin(), ray.end(), boost::bind(&RayTracingIndex::topologicalCompare, source, _1, _2));
347 
348  // remove duplicate values
349  Ray::iterator endIterator = std::unique(ray.begin(), ray.end(), &RayTracingIndex::equals);
350  ray.resize(std::distance(ray.begin(), endIterator));
351 
352  return rayTracingSucceeded;
353  }
354 
355  float getMetricWidth() {
356  return mMap.info.width * mMap.info.resolution;
357  }
358 
359  float getMetricHeight() {
360  return mMap.info.height * mMap.info.resolution;
361  }
362 
363  void worldToMapCoordinates(const SimpleVector3 &position, int32_t &x, int32_t &y) {
364  SimpleVector3 continuousMapCoords;
365  worldToMapCoordinates(position, continuousMapCoords);
366 
367  // get the map coords
368  x = (int32_t) floor(continuousMapCoords[0]);
369  y = (int32_t) floor(continuousMapCoords[1]);
370  }
371 
372  void worldToMapCoordinates(const SimpleVector3 &position, SimpleVector3 &result) {
373  SimpleVector3 translation = this->getTranslation();
374  SimpleQuaternion orientation = this->getOrientation();
375  SimpleMatrix3 rotationMatrix = orientation.toRotationMatrix();
376 
377  // the map is rotated by rotation matrix, for back transform do a transpose.
378  result = (rotationMatrix.transpose() * position - translation) / mMap.info.resolution;
379  }
380 
381  void mapToWorldCoordinates(const int32_t &x, const int32_t &y, SimpleVector3 &result) {
382  mapToWorldCoordinates(SimpleVector3(x, y, 0.0), result);
383  }
384 
385  void mapToWorldCoordinates(const SimpleVector3 &position, SimpleVector3 &result) {
386  SimpleVector3 translation = this->getTranslation();
387  SimpleQuaternion orientation = this->getOrientation();
388  result = orientation.toRotationMatrix() * position * mMap.info.resolution + translation;
389  }
390 
391  void mapToWorldSize(const double &size, double &result) {
392  result = size * mMap.info.resolution;
393  }
394 
395  void worldToMapSize(const double &size, double &result) {
396  result = size / mMap.info.resolution;
397  }
398 
400  return SimpleVector3(mMap.info.origin.position.x, mMap.info.origin.position.y, mMap.info.origin.position.z);
401  }
402 
404  return TypeHelper::getSimpleQuaternion(mMap.info.origin.orientation);
405  }
406 
407  bool isOccupancyValueAcceptable(const int8_t &occupancyValue) {
408  return occupancyValue >= 0 && occupancyValue <= mCollisionThreshold;
409  }
410 
411  void setCollisionThreshold(int8_t thresholdValue) {
412  mCollisionThreshold = thresholdValue;
413  }
414 
416  return mCollisionThreshold;
417  }
418 
419  float getSquaredDistance(const SimpleVector3 &start, const SimpleVector3 &goal) {
420  return (goal - start).squaredNorm();
421  }
422  };
423 
425 }
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:251
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:247
int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const int32_t &mapX, const int32_t &mapY)
Definition: MapHelper.hpp:200
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
bool sleep() const
void worldToMapCoordinates(const SimpleVector3 &position, int32_t &x, int32_t &y)
Definition: MapHelper.hpp:363
int8_t getMapOccupancyValue(const SimpleVector3 &position)
Definition: MapHelper.hpp:225
SimpleQuaternion getOrientation()
Definition: MapHelper.hpp:403
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:211
void setCollisionThreshold(int8_t thresholdValue)
Definition: MapHelper.hpp:411
this namespace contains all generally usable classes.
bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint, Ray &ray)
Definition: MapHelper.hpp:260
DebugHelperPtr mDebugHelperPtr
Definition: MapHelper.hpp:67
nav_msgs::OccupancyGrid mRaytracingMap
Definition: MapHelper.hpp:75
std::string getTopic() const
static boost::shared_ptr< DebugHelper > getInstance()
Definition: DebugHelper.cpp:29
void worldToMapCoordinates(const SimpleVector3 &position, SimpleVector3 &result)
Definition: MapHelper.hpp:372
ROSCPP_DECL bool ok()
void mapReceived(nav_msgs::OccupancyGrid map)
Definition: MapHelper.hpp:122
void mapToWorldCoordinates(const SimpleVector3 &position, SimpleVector3 &result)
Definition: MapHelper.hpp:385
void mapToWorldCoordinates(const int32_t &x, const int32_t &y, SimpleVector3 &result)
Definition: MapHelper.hpp:381
void worldToMapSize(const double &size, double &result)
Definition: MapHelper.hpp:395
TFSIMD_FORCE_INLINE const tfScalar & z() const
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:419
TFSIMD_FORCE_INLINE const tfScalar & w() const
int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const SimpleVector3 &position)
Definition: MapHelper.hpp:194
void mapToWorldSize(const double &size, double &result)
Definition: MapHelper.hpp:391
int8_t getRaytracingMapOccupancyValue(const SimpleVector3 &position)
Definition: MapHelper.hpp:243
Eigen::Matrix< Precision, 2, 1 > SimpleVector2
Definition: typedef.hpp:52
ros::NodeHandle mGlobalNodeHandle
Definition: MapHelper.hpp:71
bool getParam(const std::string &key, std::string &s) const
int8_t getCostmapOccupancyValue(const SimpleVector3 &position)
Definition: MapHelper.hpp:234
std::string getService()
static SimpleQuaternion getSimpleQuaternion(const geometry_msgs::Pose &pose)
Definition: TypeHelper.cpp:64
Eigen::Quaternion< Precision > SimpleQuaternion
Definition: typedef.hpp:67
bool isOccupancyValueAcceptable(const int8_t &occupancyValue)
Definition: MapHelper.hpp:407
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:229
int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const SimpleVector3 &position)
Definition: MapHelper.hpp:188
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:238
boost::shared_ptr< MapHelper > MapHelperPtr
Definition: MapHelper.hpp:424
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
SimpleVector3 getTranslation()
Definition: MapHelper.hpp:399


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 Thu Jan 9 2020 07:20:18