38 #ifndef COSTMAP_2D_COSTMAP_2D_H_ 39 #define COSTMAP_2D_COSTMAP_2D_H_ 43 #include <geometry_msgs/Point.h> 44 #include <boost/thread.hpp> 73 Costmap2D(
unsigned int cells_size_x,
unsigned int cells_size_y,
double resolution,
74 double origin_x,
double origin_y,
unsigned char default_value = 0);
97 bool copyCostmapWindow(
const Costmap2D& map,
double win_origin_x,
double win_origin_y,
double win_size_x,
116 unsigned char getCost(
unsigned int mx,
unsigned int my)
const;
124 void setCost(
unsigned int mx,
unsigned int my,
unsigned char cost);
133 void mapToWorld(
unsigned int mx,
unsigned int my,
double& wx,
double& wy)
const;
143 bool worldToMap(
double wx,
double wy,
unsigned int& mx,
unsigned int& my)
const;
153 void worldToMapNoBounds(
double wx,
double wy,
int& mx,
int& my)
const;
163 void worldToMapEnforceBounds(
double wx,
double wy,
int& mx,
int& my)
const;
171 inline unsigned int getIndex(
unsigned int mx,
unsigned int my)
const 173 return my * size_x_ + mx;
182 inline void indexToCells(
unsigned int index,
unsigned int& mx,
unsigned int& my)
const 184 my = index / size_x_;
185 mx = index - (my * size_x_);
192 unsigned char* getCharMap()
const;
198 unsigned int getSizeInCellsX()
const;
204 unsigned int getSizeInCellsY()
const;
210 double getSizeInMetersX()
const;
216 double getSizeInMetersY()
const;
222 double getOriginX()
const;
228 double getOriginY()
const;
234 double getResolution()
const;
243 return default_value_;
252 bool setConvexPolygonCost(
const std::vector<geometry_msgs::Point>& polygon,
unsigned char cost_value);
259 void polygonOutlineCells(
const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells);
266 void convexFillCells(
const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells);
273 virtual void updateOrigin(
double new_origin_x,
double new_origin_y);
279 bool saveMap(std::string file_name);
281 void resizeMap(
unsigned int size_x,
unsigned int size_y,
double resolution,
double origin_x,
284 void resetMap(
unsigned int x0,
unsigned int y0,
unsigned int xn,
unsigned int yn);
291 unsigned int cellDistance(
double world_dist);
314 template<
typename data_type>
315 void copyMapRegion(data_type* source_map,
unsigned int sm_lower_left_x,
unsigned int sm_lower_left_y,
316 unsigned int sm_size_x, data_type* dest_map,
unsigned int dm_lower_left_x,
317 unsigned int dm_lower_left_y,
unsigned int dm_size_x,
unsigned int region_size_x,
318 unsigned int region_size_y)
321 data_type* sm_index = source_map + (sm_lower_left_y * sm_size_x + sm_lower_left_x);
322 data_type* dm_index = dest_map + (dm_lower_left_y * dm_size_x + dm_lower_left_x);
325 for (
unsigned int i = 0; i < region_size_y; ++i)
327 memcpy(dm_index, sm_index, region_size_x *
sizeof(data_type));
328 sm_index += sm_size_x;
329 dm_index += dm_size_x;
336 virtual void deleteMaps();
341 virtual void resetMaps();
348 virtual void initMaps(
unsigned int size_x,
unsigned int size_y);
359 template<
class ActionType>
360 inline void raytraceLine(ActionType at,
unsigned int x0,
unsigned int y0,
unsigned int x1,
unsigned int y1,
361 unsigned int max_length = UINT_MAX)
366 unsigned int abs_dx =
abs(dx);
367 unsigned int abs_dy =
abs(dy);
369 int offset_dx =
sign(dx);
370 int offset_dy =
sign(dy) * size_x_;
372 unsigned int offset = y0 * size_x_ + x0;
375 double dist =
hypot(dx, dy);
376 double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
379 if (abs_dx >= abs_dy)
381 int error_y = abs_dx / 2;
382 bresenham2D(at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (
unsigned int)(scale * abs_dx));
387 int error_x = abs_dy / 2;
388 bresenham2D(at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (
unsigned int)(scale * abs_dy));
395 template<
class ActionType>
396 inline void bresenham2D(ActionType at,
unsigned int abs_da,
unsigned int abs_db,
int error_b,
int offset_a,
397 int offset_b,
unsigned int offset,
unsigned int max_length)
399 unsigned int end = std::min(max_length, abs_da);
400 for (
unsigned int i = 0; i < end; ++i)
405 if ((
unsigned int)error_b >= abs_da)
416 return x > 0 ? 1.0 : -1.0;
432 MarkCell(
unsigned char* costmap,
unsigned char value) :
433 costmap_(costmap), value_(value)
438 costmap_[offset] = value_;
449 costmap_(costmap), char_map_(char_map), cells_(cells)
457 costmap_.indexToCells(offset, loc.
x, loc.
y);
458 cells_.push_back(loc);
469 #endif // COSTMAP_2D_COSTMAP_2D_H
std::vector< MapLocation > & cells_
const Costmap2D & costmap_
INLINE Rall1d< T, V, S > hypot(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void bresenham2D(ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b, unsigned int offset, unsigned int max_length)
A 2D implementation of Bresenham's raytracing algorithm... applies an action at each step...
double sign(double x)
Return -1 if x < 0, +1 otherwise.
void operator()(unsigned int offset)
void setDefaultValue(unsigned char c)
void copyMapRegion(data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
Copy a region of a source map into a destination map.
void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
Raytrace a line and apply some action at each step.
boost::recursive_mutex mutex_t
PolygonOutlineCells(const Costmap2D &costmap, const unsigned char *char_map, std::vector< MapLocation > &cells)
void operator()(unsigned int offset)
const unsigned char * char_map_
MarkCell(unsigned char *costmap, unsigned char value)
unsigned char default_value_
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
unsigned char getDefaultValue()
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates.
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.