Static Public Member Functions | List of all members
mbf_costmap_nav::FootprintHelper Class Reference

#include <footprint_helper.h>

Static Public Member Functions

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< CellgetFootprintCells (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...
 

Detailed Description

Definition at line 89 of file footprint_helper.h.

Member Function Documentation

◆ 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
footprintThe 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()

std::vector< Cell > mbf_costmap_nav::FootprintHelper::getFootprintCells ( double  x,
double  y,
double  theta,
const std::vector< geometry_msgs::Point > &  footprint_spec,
const costmap_2d::Costmap2D costmap,
bool  fill 
)
static

Used to get the cells that make up the footprint of the robot.

Parameters
xThe x position of the robot
yThe y position of the robot
thetaThe orientation of the robot
fillIf 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
x0The x coordinate of the first point
x1The x coordinate of the second point
y0The y coordinate of the first point
y1The y coordinate of the second point
ptsWill 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:


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:55