Public Member Functions
base_local_planner::FootprintHelper Class Reference

#include <footprint_helper.h>

List of all members.

Public Member Functions

 FootprintHelper ()
void getFillCells (std::vector< base_local_planner::Position2DInt > &footprint)
 Fill the outline of a polygon, in this case the robot footprint, in a grid.
std::vector
< base_local_planner::Position2DInt > 
getFootprintCells (Eigen::Vector3f pos, 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.
void getLineCells (int x0, int x1, int y0, int y1, std::vector< base_local_planner::Position2DInt > &pts)
 Use Bresenham's algorithm to trace a line between two points in a grid.
virtual ~FootprintHelper ()

Detailed Description

Definition at line 50 of file footprint_helper.h.


Constructor & Destructor Documentation

Definition at line 42 of file footprint_helper.cpp.

Definition at line 47 of file footprint_helper.cpp.


Member Function Documentation

void base_local_planner::FootprintHelper::getFillCells ( std::vector< base_local_planner::Position2DInt > &  footprint)

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 123 of file footprint_helper.cpp.

std::vector< base_local_planner::Position2DInt > base_local_planner::FootprintHelper::getFootprintCells ( Eigen::Vector3f  pos,
std::vector< geometry_msgs::Point footprint_spec,
const costmap_2d::Costmap2D costmap,
bool  fill 
)

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

Parameters:
x_iThe x position of the robot
y_iThe y position of the robot
theta_iThe 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 cellsof a footprint at a given position

Definition at line 180 of file footprint_helper.cpp.

void base_local_planner::FootprintHelper::getLineCells ( int  x0,
int  x1,
int  y0,
int  y1,
std::vector< base_local_planner::Position2DInt > &  pts 
)

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 51 of file footprint_helper.cpp.


The documentation for this class was generated from the following files:


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:30