EasyNav Costmap Stack
Loading...
Searching...
No Matches
costmap_2d.hpp
Go to the documentation of this file.
1/*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, 2013, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 * David V. Lu!!
37 *********************************************************************/
38#ifndef EASYNAV_COSTMAP_COMMON__COSTMAP_2D_HPP_
39#define EASYNAV_COSTMAP_COMMON__COSTMAP_2D_HPP_
40
41#include <string.h>
42#include <stdio.h>
43#include <limits.h>
44#include <algorithm>
45#include <cmath>
46#include <string>
47#include <vector>
48#include <queue>
49#include <mutex>
50#include "geometry_msgs/msg/point.hpp"
51#include "nav_msgs/msg/occupancy_grid.hpp"
52
53namespace easynav
54{
55
56// convenient for storing x/y point pairs
58{
59 unsigned int x;
60 unsigned int y;
61 unsigned char cost;
62};
63
69{
70 friend class CostmapTester; // Need this for gtest to work correctly
71
72public:
83 unsigned int cells_size_x, unsigned int cells_size_y, double resolution,
84 double origin_x, double origin_y, unsigned char default_value = 0);
85
90 Costmap2D(const Costmap2D & map);
91
96 explicit Costmap2D(const nav_msgs::msg::OccupancyGrid & map);
97
103 Costmap2D & operator=(const Costmap2D & map);
104
111 bool inBounds(unsigned int x, unsigned int y) const;
112
122 const Costmap2D & map, double win_origin_x, double win_origin_y,
123 double win_size_x,
124 double win_size_y);
125
134 void toOccupancyGridMsg(nav_msgs::msg::OccupancyGrid & msg) const;
135
147 bool copyWindow(
148 const Costmap2D & source,
149 unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn,
150 unsigned int dx0, unsigned int dy0);
151
155 Costmap2D();
156
160 virtual ~Costmap2D();
161
168 unsigned char getCost(unsigned int mx, unsigned int my) const;
169
175 unsigned char getCost(unsigned int index) const;
176
183 void setCost(unsigned int mx, unsigned int my, unsigned char cost);
184
192 void mapToWorld(unsigned int mx, unsigned int my, double & wx, double & wy) const;
193
201 void mapToWorldNoBounds(int mx, int my, double & wx, double & wy) const;
202
211 bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const;
212
221 bool worldToMapContinuous(double wx, double wy, float & mx, float & my) const;
222
231 void worldToMapNoBounds(double wx, double wy, int & mx, int & my) const;
232
241 void worldToMapEnforceBounds(double wx, double wy, int & mx, int & my) const;
242
249 inline unsigned int getIndex(unsigned int mx, unsigned int my) const
250 {
251 return my * size_x_ + mx;
252 }
253
260 inline void indexToCells(unsigned int index, unsigned int & mx, unsigned int & my) const
261 {
262 my = index / size_x_;
263 mx = index - (my * size_x_);
264 }
265
270 unsigned char * getCharMap() const;
271
276 unsigned int getSizeInCellsX() const;
277
282 unsigned int getSizeInCellsY() const;
283
288 double getSizeInMetersX() const;
289
294 double getSizeInMetersY() const;
295
300 double getOriginX() const;
301
306 double getOriginY() const;
307
312 double getResolution() const;
313
318 void setDefaultValue(unsigned char c)
319 {
320 default_value_ = c;
321 }
322
327 unsigned char getDefaultValue()
328 {
329 return default_value_;
330 }
331
339 const std::vector<geometry_msgs::msg::Point> & polygon,
340 unsigned char cost_value);
341
349 const std::vector<geometry_msgs::msg::Point> & polygon,
350 std::vector<MapLocation> & polygon_map_region);
351
358 const std::vector<MapLocation> & polygon_map_region,
359 unsigned char new_cost_value);
360
366 const std::vector<MapLocation> & polygon_map_region);
367
374 const std::vector<MapLocation> & polygon,
375 std::vector<MapLocation> & polygon_cells);
376
382 void convexFillCells(
383 const std::vector<MapLocation> & polygon,
384 std::vector<MapLocation> & polygon_cells);
385
391 virtual void updateOrigin(double new_origin_x, double new_origin_y);
392
396 void resizeMap(
397 unsigned int size_x, unsigned int size_y, double resolution, double origin_x,
398 double origin_y);
399
403 void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn);
404
408 void resetMapToValue(
409 unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value);
410
416 unsigned int cellDistance(double world_dist);
417
418 // Provide a typedef to ease future code maintenance
419 typedef std::recursive_mutex mutex_t;
421 {
422 return access_;
423 }
424
425protected:
439 template<typename data_type>
441 data_type * source_map, unsigned int sm_lower_left_x,
442 unsigned int sm_lower_left_y,
443 unsigned int sm_size_x, data_type * dest_map, unsigned int dm_lower_left_x,
444 unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x,
445 unsigned int region_size_y)
446 {
447 // we'll first need to compute the starting points for each map
448 data_type * sm_index = source_map + (sm_lower_left_y * sm_size_x + sm_lower_left_x);
449 data_type * dm_index = dest_map + (dm_lower_left_y * dm_size_x + dm_lower_left_x);
450
451 // now, we'll copy the source map into the destination map
452 for (unsigned int i = 0; i < region_size_y; ++i) {
453 memcpy(dm_index, sm_index, region_size_x * sizeof(data_type));
454 sm_index += sm_size_x;
455 dm_index += dm_size_x;
456 }
457 }
458
462 virtual void deleteMaps();
463
467 virtual void resetMaps();
468
474 virtual void initMaps(unsigned int size_x, unsigned int size_y);
475
487 template<class ActionType>
488 inline void raytraceLine(
489 ActionType at, unsigned int x0, unsigned int y0, unsigned int x1,
490 unsigned int y1,
491 unsigned int max_length = UINT_MAX, unsigned int min_length = 0)
492 {
493 int dx_full = x1 - x0;
494 int dy_full = y1 - y0;
495
496 // we need to chose how much to scale our dominant dimension,
497 // based on the maximum length of the line
498 double dist = std::hypot(dx_full, dy_full);
499 if (dist < min_length) {
500 return;
501 }
502
503 unsigned int min_x0, min_y0;
504 if (dist > 0.0) {
505 // Adjust starting point and offset to start from min_length distance
506 min_x0 = (unsigned int)(x0 + dx_full / dist * min_length);
507 min_y0 = (unsigned int)(y0 + dy_full / dist * min_length);
508 } else {
509 // dist can be 0 if [x0, y0]==[x1, y1].
510 // In this case only this cell should be processed.
511 min_x0 = x0;
512 min_y0 = y0;
513 }
514 unsigned int offset = min_y0 * size_x_ + min_x0;
515
516 int dx = x1 - min_x0;
517 int dy = y1 - min_y0;
518
519 unsigned int abs_dx = abs(dx);
520 unsigned int abs_dy = abs(dy);
521
522 int offset_dx = sign(dx);
523 int offset_dy = sign(dy) * size_x_;
524
525 double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
526 // if x is dominant
527 if (abs_dx >= abs_dy) {
528 int error_y = abs_dx / 2;
529
530 bresenham2D(
531 at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (unsigned int)(scale * abs_dx));
532 return;
533 }
534
535 // otherwise y is dominant
536 int error_x = abs_dy / 2;
537
538 bresenham2D(
539 at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (unsigned int)(scale * abs_dy));
540 }
541
542private:
547 template<class ActionType>
548 inline void bresenham2D(
549 ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b,
550 int offset_a,
551 int offset_b, unsigned int offset,
552 unsigned int max_length)
553 {
554 unsigned int end = std::min(max_length, abs_da);
555 for (unsigned int i = 0; i < end; ++i) {
556 at(offset);
557 offset += offset_a;
558 error_b += abs_db;
559 if ((unsigned int)error_b >= abs_da) {
560 offset += offset_b;
561 error_b -= abs_da;
562 }
563 }
564 at(offset);
565 }
566
570 inline int sign(int x)
571 {
572 return x > 0 ? 1.0 : -1.0;
573 }
574
575 mutex_t * access_;
576
577protected:
578 unsigned int size_x_;
579 unsigned int size_y_;
581 double origin_x_;
582 double origin_y_;
583 unsigned char * costmap_;
584 unsigned char default_value_;
585
586 // *INDENT-OFF* Uncrustify doesn't handle indented public/private labels
588 {
589 public:
590 MarkCell(unsigned char * costmap, unsigned char value)
591 : costmap_(costmap), value_(value)
592 {
593 }
594 inline void operator()(unsigned int offset)
595 {
596 costmap_[offset] = value_;
597 }
598
599 private:
600 unsigned char * costmap_;
601 unsigned char value_;
602 };
603
605 {
606 public:
608 const Costmap2D & costmap, const unsigned char * /*char_map*/,
609 std::vector<MapLocation> & cells)
610 : costmap_(costmap), cells_(cells)
611 {
612 }
613
614 // just push the relevant cells back onto the list
615 inline void operator()(unsigned int offset)
616 {
617 MapLocation loc;
618 costmap_.indexToCells(offset, loc.x, loc.y);
619 loc.cost = costmap_.getCost(loc.x, loc.y);
620 cells_.push_back(loc);
621 }
622
623 private:
624 const Costmap2D & costmap_;
625 std::vector<MapLocation> & cells_;
626 };
627 // *INDENT-ON*
628};
629} // namespace easynav
630
631#endif // EASYNAV_COSTMAP_COMMON__COSTMAP_2D_HPP_
MarkCell(unsigned char *costmap, unsigned char value)
Definition costmap_2d.hpp:590
PolygonOutlineCells(const Costmap2D &costmap, const unsigned char *, std::vector< MapLocation > &cells)
Definition costmap_2d.hpp:607
Costmap2D(unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
Constructor for a costmap.
Definition costmap_2d.cpp:54
MarkCell(unsigned char *costmap, unsigned char value)
Definition costmap_2d.hpp:590
void operator()(unsigned int offset)
Definition costmap_2d.hpp:594
PolygonOutlineCells(const Costmap2D &costmap, const unsigned char *, std::vector< MapLocation > &cells)
Definition costmap_2d.hpp:607
void operator()(unsigned int offset)
Definition costmap_2d.hpp:615
Costmap2D()
Default constructor.
Definition costmap_2d.cpp:272
void polygonOutlineCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that make up the outline of a polygon.
Definition costmap_2d.cpp:495
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition costmap_2d.cpp:295
bool inBounds(unsigned int x, unsigned int y) const
Checks whether a given cell coordinate is within the bounds of the costmap.
Definition costmap_2d.cpp:284
double getResolution() const
Accessor for the resolution of the costmap.
Definition costmap_2d.cpp:612
void setDefaultValue(unsigned char c)
Set the default background value of the costmap.
Definition costmap_2d.hpp:318
unsigned int size_x_
Definition costmap_2d.hpp:578
Costmap2D & operator=(const Costmap2D &map)
Overloaded assignment operator.
Definition costmap_2d.cpp:238
bool copyWindow(const Costmap2D &source, unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn, unsigned int dx0, unsigned int dy0)
Copies the (x0,y0)..(xn,yn) window from source costmap into a current costmap.
Definition costmap_2d.cpp:189
void mapToWorldNoBounds(int mx, int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates with no bounds checking.
Definition costmap_2d.cpp:321
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates.
Definition costmap_2d.hpp:260
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition costmap_2d.cpp:597
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition costmap_2d.cpp:289
virtual void initMaps(unsigned int size_x, unsigned int size_y)
Initializes the costmap, static_map, and markers data structures.
Definition costmap_2d.cpp:106
Costmap2D(unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
Constructor for a costmap.
Definition costmap_2d.cpp:54
bool copyCostmapWindow(const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
Turn this costmap into a copy of a window of a costmap passed in.
Definition costmap_2d.cpp:150
virtual void deleteMaps()
Deletes the costmap, static_map, and markers data structures.
Definition costmap_2d.cpp:98
void restoreMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region)
Restores the corresponding map region using given map region.
Definition costmap_2d.cpp:465
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition costmap_2d.cpp:582
double getOriginX() const
Accessor for the x origin of the costmap.
Definition costmap_2d.cpp:602
double resolution_
Definition costmap_2d.hpp:580
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition costmap_2d.cpp:310
void worldToMapEnforceBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates, constraining results to legal bounds.
Definition costmap_2d.cpp:363
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition costmap_2d.cpp:129
void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX, unsigned int min_length=0)
Raytrace a line and apply some action at each step.
Definition costmap_2d.hpp:488
bool worldToMapContinuous(double wx, double wy, float &mx, float &my) const
Convert from world coordinates to map coordinates.
Definition costmap_2d.cpp:342
virtual void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location....
Definition costmap_2d.cpp:385
bool getMapRegionOccupiedByPolygon(const std::vector< geometry_msgs::msg::Point > &polygon, std::vector< MapLocation > &polygon_map_region)
Gets the map region occupied by polygon.
Definition costmap_2d.cpp:473
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition costmap_2d.cpp:327
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition costmap_2d.cpp:587
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition costmap_2d.hpp:249
unsigned char * costmap_
Definition costmap_2d.hpp:583
friend class CostmapTester
Definition costmap_2d.hpp:70
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.
Definition costmap_2d.hpp:440
unsigned char getDefaultValue()
Get the default background value of the costmap.
Definition costmap_2d.hpp:327
void worldToMapNoBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates without checking for legal bounds.
Definition costmap_2d.cpp:357
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition costmap_2d.cpp:300
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
Definition costmap_2d.cpp:115
void toOccupancyGridMsg(nav_msgs::msg::OccupancyGrid &msg) const
Converts the current costmap into a nav_msgs::msg::OccupancyGrid message.
Definition costmap_2d.cpp:213
void resetMapToValue(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value)
Reset the costmap in bounds to a value.
Definition costmap_2d.cpp:140
std::recursive_mutex mutex_t
Definition costmap_2d.hpp:419
unsigned int size_y_
Definition costmap_2d.hpp:579
void setMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region, unsigned char new_cost_value)
Sets the given map region to desired value.
Definition costmap_2d.cpp:456
bool setConvexPolygonCost(const std::vector< geometry_msgs::msg::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
Definition costmap_2d.cpp:441
double origin_y_
Definition costmap_2d.hpp:582
double getOriginY() const
Accessor for the y origin of the costmap.
Definition costmap_2d.cpp:607
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition costmap_2d.cpp:315
virtual ~Costmap2D()
Destructor.
Definition costmap_2d.cpp:278
mutex_t * getMutex()
Definition costmap_2d.hpp:420
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
Definition costmap_2d.cpp:135
double origin_x_
Definition costmap_2d.hpp:581
unsigned char default_value_
Definition costmap_2d.hpp:584
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition costmap_2d.cpp:592
void convexFillCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that fill a convex polygon.
Definition costmap_2d.cpp:512
Provides a mapping for often used cost values.
Definition cost_values.hpp:41
Definition costmap_2d.hpp:58
unsigned char cost
Definition costmap_2d.hpp:61
unsigned int x
Definition costmap_2d.hpp:59
unsigned int y
Definition costmap_2d.hpp:60