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> 30 #include <boost/tuple/tuple.hpp> 31 #include <costmap_2d/costmap_2d_ros.h> 52 return (firstIndexVector - sourceVector).squaredNorm() < (secondIndexVector - sourceVector).squaredNorm();
58 return firstIndexVector == secondIndexVector;
62 typedef std::vector<RayTracingIndex>
Ray;
73 nav_msgs::OccupancyGrid
mMap;
77 int8_t mCostTranslationTable[256];
79 MapHelper(
const std::string &mapTopicName =
"map",
const std::string &getPlanServiceName =
"move_base/make_plan") : mMapReceived(false), mCollisionThreshold(45) {
83 mCostTranslationTable[0] = 0;
84 mCostTranslationTable[253] = 99;
85 mCostTranslationTable[254] = 100;
86 mCostTranslationTable[255] = -1;
89 for (
int i = 1; i < 253; i++) {
90 mCostTranslationTable[i] = int8_t(1 + (97 * (i - 1)) / 251);
95 while(
ros::ok() && !mMapReceived) {
96 mDebugHelperPtr->write(std::stringstream() <<
"Waiting for map to arrive on topic '" << mapSubscriber.
getTopic() <<
"'",
104 mDebugHelperPtr->write(std::stringstream() <<
"waiting for service: " << getPlanServiceName,
DebugHelper::MAP);
106 mGetPlanServiceClient = mGlobalNodeHandle.
serviceClient<nav_msgs::GetPlan>(getPlanServiceName,
true);
108 mDebugHelperPtr->write(std::stringstream() <<
"Waiting for planning server to start on service '" 114 this->aggregateRaytracingMap();
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);
142 std::string name =
"global_costmap";
143 costmap_2d::Costmap2DROS costmapRos(name, tf);
145 costmapRos.updateMap();
148 mCostmap = *(costmapRos.getCostmap());
152 mGlobalNodeHandle.
getParam(
"/nbv/mMapsImagePath", path);
155 std::string costmapPath = path +
"/costmap.pgm";
156 mDebugHelperPtr->write(
"Outputting calculated costmap to " + costmapPath,
158 mCostmap.saveMap(costmapPath);
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());
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;
182 mRaytracingMap.data[index] = aggregatedOccupancyValue;
190 this->worldToMapCoordinates(position, mapX, mapY);
191 return this->getOccupancyValue(map, mapX, mapY);
196 this->worldToMapCoordinates(position, mapX, mapY);
197 return this->getOccupancyValue(costmap, mapX, mapY);
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;
204 if (mapX < 0 || mapY < 0 || mapX >= (int32_t)width || mapY >= (int32_t)height) {
208 return map.data[mapX + mapY * width];
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();
215 if (mapX < 0 || mapY < 0 || mapX >= (int32_t)width || mapY >= (int32_t)height) {
219 unsigned char cost = costmap.getCost(mapX, mapY);
220 return mCostTranslationTable[cost];
226 return this->getOccupancyValue(mMap, position);
230 return this->getOccupancyValue(mMap, mapX, mapY);
235 return this->getOccupancyValue(mCostmap, position);
239 return this->getOccupancyValue(mCostmap, mapX, mapY);
244 return this->getOccupancyValue(mRaytracingMap, position);
248 return this->getOccupancyValue(mRaytracingMap, mapX, mapY);
253 bool retVal = this->doRaytracing(fromPoint, toPoint, ray);
265 int32_t fromMapX, fromMapY;
266 this->worldToMapCoordinates(fromPoint, fromMapX, fromMapY);
268 int32_t toMapX, toMapY;
269 this->worldToMapCoordinates(toPoint, toMapX, toMapY);
272 int32_t distanceX = toMapX - fromMapX;
273 int32_t distanceY = toMapY - fromMapY;
276 if (distanceX == 0 && distanceY == 0) {
277 int8_t occupancyValue = this->getRaytracingMapOccupancyValue(fromMapX, fromMapY);
278 return this->isOccupancyValueAcceptable(occupancyValue);
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);
288 float resolution = mRaytracingMap.info.resolution;
291 int32_t signumX = distanceX < 0 ? - 1 : 1;
292 int32_t signumY = distanceY < 0 ? - 1 : 1;
295 SimpleVector2 diff = (toPoint - fromPoint).block<2, 1>(0, 0);
298 bool rayTracingSucceeded =
true;
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];
307 idx.
x = (int32_t) (x / resolution);
308 idx.
y = (int32_t) (y / resolution);
309 idx.
occupancy = this->getRaytracingMapOccupancyValue(idx.
x, idx.
y);
311 if (idx.
x < minX || idx.
x > maxX || idx.
y < minY || idx.
y > maxY) {
315 if (!this->isOccupancyValueAcceptable(idx.
occupancy)) {
316 rayTracingSucceeded =
false;
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];
329 idx.
x = (int32_t) (x / resolution);
330 idx.
y = (int32_t) (y / resolution);
331 idx.
occupancy = this->getRaytracingMapOccupancyValue(idx.
x, idx.
y);
333 if (idx.
x < minX || idx.
x > maxX || idx.
y < minY || idx.
y > maxY) {
337 if (!this->isOccupancyValueAcceptable(idx.
occupancy)) {
338 rayTracingSucceeded =
false;
350 ray.resize(std::distance(ray.begin(), endIterator));
352 return rayTracingSucceeded;
356 return mMap.info.width * mMap.info.resolution;
360 return mMap.info.height * mMap.info.resolution;
365 worldToMapCoordinates(position, continuousMapCoords);
368 x = (int32_t) floor(continuousMapCoords[0]);
369 y = (int32_t) floor(continuousMapCoords[1]);
375 SimpleMatrix3 rotationMatrix = orientation.toRotationMatrix();
378 result = (rotationMatrix.transpose() * position - translation) / mMap.info.resolution;
388 result = orientation.toRotationMatrix() * position * mMap.info.resolution + translation;
392 result = size * mMap.info.resolution;
396 result = size / mMap.info.resolution;
400 return SimpleVector3(mMap.info.origin.position.x, mMap.info.origin.position.y, mMap.info.origin.position.z);
408 return occupancyValue >= 0 && occupancyValue <= mCollisionThreshold;
412 mCollisionThreshold = thresholdValue;
416 return mCollisionThreshold;
420 return (goal - start).squaredNorm();
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)
static bool topologicalCompare(const RayTracingIndex &source, const RayTracingIndex &firstIndex, const RayTracingIndex &secondIndex)
int8_t getRaytracingMapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const int32_t &mapX, const int32_t &mapY)
static bool equals(const RayTracingIndex &firstIndex, const RayTracingIndex &secondIndex)
ros::ServiceClient mGetPlanServiceClient
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
void worldToMapCoordinates(const SimpleVector3 &position, int32_t &x, int32_t &y)
int8_t getMapOccupancyValue(const SimpleVector3 &position)
SimpleQuaternion getOrientation()
boost::shared_ptr< RayTracingIndex > RayTracingIndexPtr
nav_msgs::OccupancyGrid mMap
int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const int32_t &mapX, const int32_t &mapY)
void setCollisionThreshold(int8_t thresholdValue)
this namespace contains all generally usable classes.
bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint, Ray &ray)
DebugHelperPtr mDebugHelperPtr
int8_t mCollisionThreshold
nav_msgs::OccupancyGrid mRaytracingMap
std::string getTopic() const
static boost::shared_ptr< DebugHelper > getInstance()
void worldToMapCoordinates(const SimpleVector3 &position, SimpleVector3 &result)
void aggregateRaytracingMap()
void mapReceived(nav_msgs::OccupancyGrid map)
void mapToWorldCoordinates(const SimpleVector3 &position, SimpleVector3 &result)
void mapToWorldCoordinates(const int32_t &x, const int32_t &y, SimpleVector3 &result)
void worldToMapSize(const double &size, double &result)
TFSIMD_FORCE_INLINE const tfScalar & z() const
costmap_2d::Costmap2D mCostmap
std::vector< RayTracingIndex > Ray
float getSquaredDistance(const SimpleVector3 &start, const SimpleVector3 &goal)
TFSIMD_FORCE_INLINE const tfScalar & w() const
int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const SimpleVector3 &position)
void mapToWorldSize(const double &size, double &result)
int8_t getRaytracingMapOccupancyValue(const SimpleVector3 &position)
Eigen::Matrix< Precision, 2, 1 > SimpleVector2
ros::NodeHandle mGlobalNodeHandle
bool getParam(const std::string &key, std::string &s) const
int8_t getCostmapOccupancyValue(const SimpleVector3 &position)
static SimpleQuaternion getSimpleQuaternion(const geometry_msgs::Pose &pose)
int8_t getCollisionThreshold()
Eigen::Quaternion< Precision > SimpleQuaternion
bool isOccupancyValueAcceptable(const int8_t &occupancyValue)
ROSCPP_DECL void spinOnce()
Eigen::Matrix< Precision, 3, 3 > SimpleMatrix3
int8_t getMapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const SimpleVector3 &position)
MapHelper(const std::string &mapTopicName="map", const std::string &getPlanServiceName="move_base/make_plan")
int8_t getCostmapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
boost::shared_ptr< MapHelper > MapHelperPtr
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
SimpleVector3 getTranslation()