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> 50 return (firstIndexVector - sourceVector).squaredNorm() < (secondIndexVector - sourceVector).squaredNorm();
56 return firstIndexVector == secondIndexVector;
60 typedef std::vector<RayTracingIndex>
Ray;
71 nav_msgs::OccupancyGrid
mMap;
75 int8_t mCostTranslationTable[256];
77 MapHelper(
const std::string &mapTopicName =
"map",
const std::string &getPlanServiceName =
"move_base/make_plan") : mMapReceived(false), mCollisionThreshold(45) {
81 mCostTranslationTable[0] = 0;
82 mCostTranslationTable[253] = 99;
83 mCostTranslationTable[254] = 100;
84 mCostTranslationTable[255] = -1;
86 for (
int i = 1; i < 253; i++) {
87 mCostTranslationTable[i] = int8_t(1 + (97 * (i - 1)) / 251);
91 while(
ros::ok() && !mMapReceived) {
92 mDebugHelperPtr->write(std::stringstream() <<
"Waiting for map to arrive on topic '" << mapSubscriber.
getTopic() <<
"'",
99 mDebugHelperPtr->write(std::stringstream() <<
"waiting for service: " << getPlanServiceName,
DebugHelper::MAP);
101 mGetPlanServiceClient = mGlobalNodeHandle.
serviceClient<nav_msgs::GetPlan>(getPlanServiceName,
true);
103 mDebugHelperPtr->write(std::stringstream() <<
"Waiting for planning server to start on service '" 109 this->aggregateRaytracingMap();
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);
134 std::string name =
"global_costmap";
144 mGlobalNodeHandle.
getParam(
"/nbv/mMapsImagePath", path);
147 std::string costmapPath = path +
"/costmap.pgm";
148 mDebugHelperPtr->write(
"Outputting calculated costmap to " + costmapPath,
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);
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;
171 mRaytracingMap.data[index] = aggregatedOccupancyValue;
179 this->worldToMapCoordinates(position, mapX, mapY);
180 return this->getOccupancyValue(map, mapX, mapY);
185 this->worldToMapCoordinates(position, mapX, mapY);
186 return this->getOccupancyValue(costmap, mapX, mapY);
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;
193 if (mapX < 0 || mapY < 0 || mapX >= (int32_t)width || mapY >= (int32_t)height) {
197 return map.data[mapX + mapY * width];
204 if (mapX < 0 || mapY < 0 || mapX >= (int32_t)width || mapY >= (int32_t)height) {
208 unsigned char cost = costmap.
getCost(mapX, mapY);
209 return mCostTranslationTable[cost];
214 return this->getOccupancyValue(mMap, position);
218 return this->getOccupancyValue(mMap, mapX, mapY);
223 return this->getOccupancyValue(mCostmap, position);
227 return this->getOccupancyValue(mCostmap, mapX, mapY);
232 return this->getOccupancyValue(mRaytracingMap, position);
236 return this->getOccupancyValue(mRaytracingMap, mapX, mapY);
241 bool retVal = this->doRaytracing(fromPoint, toPoint, ray);
250 int32_t fromMapX, fromMapY;
251 this->worldToMapCoordinates(fromPoint, fromMapX, fromMapY);
253 int32_t toMapX, toMapY;
254 this->worldToMapCoordinates(toPoint, toMapX, toMapY);
257 int32_t distanceX = toMapX - fromMapX;
258 int32_t distanceY = toMapY - fromMapY;
261 if (distanceX == 0 && distanceY == 0) {
262 int8_t occupancyValue = this->getRaytracingMapOccupancyValue(fromMapX, fromMapY);
263 return this->isOccupancyValueAcceptable(occupancyValue);
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);
273 float resolution = mRaytracingMap.info.resolution;
276 int32_t signumX = distanceX < 0 ? - 1 : 1;
277 int32_t signumY = distanceY < 0 ? - 1 : 1;
283 bool rayTracingSucceeded =
true;
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];
292 idx.
x = (int32_t) (x / resolution);
293 idx.
y = (int32_t) (y / resolution);
294 idx.
occupancy = this->getRaytracingMapOccupancyValue(idx.
x, idx.
y);
296 if (idx.
x < minX || idx.
x > maxX || idx.
y < minY || idx.
y > maxY) {
300 if (!this->isOccupancyValueAcceptable(idx.
occupancy)) {
301 rayTracingSucceeded =
false;
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];
314 idx.
x = (int32_t) (x / resolution);
315 idx.
y = (int32_t) (y / resolution);
316 idx.
occupancy = this->getRaytracingMapOccupancyValue(idx.
x, idx.
y);
318 if (idx.
x < minX || idx.
x > maxX || idx.
y < minY || idx.
y > maxY) {
322 if (!this->isOccupancyValueAcceptable(idx.
occupancy)) {
323 rayTracingSucceeded =
false;
335 ray.resize(std::distance(ray.begin(), endIterator));
337 return rayTracingSucceeded;
341 return mMap.info.width * mMap.info.resolution;
345 return mMap.info.height * mMap.info.resolution;
350 worldToMapCoordinates(position, continuousMapCoords);
353 x = (int32_t) floor(continuousMapCoords[0]);
354 y = (int32_t) floor(continuousMapCoords[1]);
360 SimpleMatrix3 rotationMatrix = orientation.toRotationMatrix();
363 result = (rotationMatrix.transpose() * position - translation) / mMap.info.resolution;
373 result = orientation.toRotationMatrix() * position * mMap.info.resolution + translation;
377 result = size * mMap.info.resolution;
381 result = size / mMap.info.resolution;
385 return SimpleVector3(mMap.info.origin.position.x, mMap.info.origin.position.y, mMap.info.origin.position.z);
393 return occupancyValue >= 0 && occupancyValue <= mCollisionThreshold;
397 mCollisionThreshold = thresholdValue;
401 return mCollisionThreshold;
405 return (goal - start).squaredNorm();
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)
Eigen::Matrix< Precision, 2, 1 > SimpleVector2
void worldToMapCoordinates(const SimpleVector3 &position, SimpleVector3 &result)
costmap_2d::Costmap2D mCostmap
unsigned int getSizeInCellsY() const
float getSquaredDistance(const SimpleVector3 &start, const SimpleVector3 &goal)
int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const int32_t &mapX, const int32_t &mapY)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int8_t mCollisionThreshold
bool isOccupancyValueAcceptable(const int8_t &occupancyValue)
void setCollisionThreshold(int8_t thresholdValue)
static boost::shared_ptr< DebugHelper > getInstance()
int8_t getCollisionThreshold()
int8_t getMapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
ros::NodeHandle mGlobalNodeHandle
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)
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
void mapToWorldCoordinates(const SimpleVector3 &position, SimpleVector3 &result)
void aggregateRaytracingMap()
geometry_msgs::TransformStamped t
int8_t getOccupancyValue(const nav_msgs::OccupancyGrid &map, const SimpleVector3 &position)
int8_t getRaytracingMapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint, Ray &ray)
boost::shared_ptr< MapHelper > MapHelperPtr
ros::ServiceClient mGetPlanServiceClient
std::vector< RayTracingIndex > Ray
int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const int32_t &mapX, const int32_t &mapY)
void mapToWorldSize(const double &size, double &result)
int8_t getCostmapOccupancyValue(const int32_t &mapX, const int32_t &mapY)
int8_t getMapOccupancyValue(const SimpleVector3 &position)
void worldToMapSize(const double &size, double &result)
bool saveMap(std::string file_name)
int8_t getRaytracingMapOccupancyValue(const SimpleVector3 &position)
bool getParam(const std::string &key, std::string &s) const
nav_msgs::OccupancyGrid mMap
int8_t getCostmapOccupancyValue(const SimpleVector3 &position)
this namespace contains all generally usable classes.
static bool equals(const RayTracingIndex &firstIndex, const RayTracingIndex &secondIndex)
bool doRaytracing(const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint)
SimpleQuaternion getOrientation()
void worldToMapCoordinates(const SimpleVector3 &position, int32_t &x, int32_t &y)
MapHelper(const std::string &mapTopicName="map", const std::string &getPlanServiceName="move_base/make_plan")
static bool topologicalCompare(const RayTracingIndex &source, const RayTracingIndex &firstIndex, const RayTracingIndex &secondIndex)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
Eigen::Matrix< Precision, 3, 3 > SimpleMatrix3
boost::shared_ptr< RayTracingIndex > RayTracingIndexPtr
void mapReceived(nav_msgs::OccupancyGrid map)
nav_msgs::OccupancyGrid mRaytracingMap
int8_t getOccupancyValue(const costmap_2d::Costmap2D &costmap, const SimpleVector3 &position)
ROSCPP_DECL void spinOnce()
DebugHelperPtr mDebugHelperPtr
SimpleVector3 getTranslation()
Eigen::Quaternion< Precision > SimpleQuaternion
unsigned char getCost(unsigned int mx, unsigned int my) const
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)