#include <footprint_helper.h>
|
static void | getFillCells (std::vector< Cell > &footprint) |
| Fill the outline of a polygon, in this case the robot footprint, in a grid. More...
|
|
static std::vector< Cell > | getFootprintCells (double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, const costmap_2d::Costmap2D &, bool fill) |
| Used to get the cells that make up the footprint of the robot. More...
|
|
static void | getLineCells (int x0, int x1, int y0, int y1, std::vector< Cell > &pts) |
| Use Bresenham's algorithm to trace a line between two points in a grid. More...
|
|
Definition at line 89 of file footprint_helper.h.
◆ getFillCells()
void mbf_costmap_nav::FootprintHelper::getFillCells |
( |
std::vector< Cell > & |
footprint | ) |
|
|
static |
Fill the outline of a polygon, in this case the robot footprint, in a grid.
- Parameters
-
footprint | The list of cells making up the footprint in the grid, will be modified to include all cells inside the footprint |
Definition at line 150 of file footprint_helper.cpp.
◆ getFootprintCells()
Used to get the cells that make up the footprint of the robot.
- Parameters
-
x | The x position of the robot |
y | The y position of the robot |
theta | The orientation of the robot |
fill | If true: returns all cells in the footprint of the robot. If false: returns only the cells that make up the outline of the footprint. |
- Returns
- The cells that make up either the outline or entire footprint of the robot depending on fill
get the cells of a footprint at a given position
Definition at line 216 of file footprint_helper.cpp.
◆ getLineCells()
void mbf_costmap_nav::FootprintHelper::getLineCells |
( |
int |
x0, |
|
|
int |
x1, |
|
|
int |
y0, |
|
|
int |
y1, |
|
|
std::vector< Cell > & |
pts |
|
) |
| |
|
static |
Use Bresenham's algorithm to trace a line between two points in a grid.
- Parameters
-
x0 | The x coordinate of the first point |
x1 | The x coordinate of the second point |
y0 | The y coordinate of the first point |
y1 | The y coordinate of the second point |
pts | Will be filled with the cells that lie on the line in the grid |
Definition at line 78 of file footprint_helper.cpp.
The documentation for this class was generated from the following files: