Public Member Functions
teb_local_planner::BaseRobotFootprintModel Class Reference

Abstract class that defines the interface for robot footprint/contour models. More...

#include <robot_footprint_model.h>

Inheritance diagram for teb_local_planner::BaseRobotFootprintModel:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 BaseRobotFootprintModel ()
 Default constructor of the abstract obstacle class.
virtual double calculateDistance (const PoseSE2 &current_pose, const Obstacle *obstacle) const =0
 Calculate the distance between the robot and an obstacle.
virtual double getInscribedRadius ()=0
 Compute the inscribed radius of the footprint model.
virtual void visualizeRobot (const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
 Visualize the robot using a markers.
virtual ~BaseRobotFootprintModel ()
 Virtual destructor.

Detailed Description

Abstract class that defines the interface for robot footprint/contour models.

The robot model class is currently used in optimization only, since taking the navigation stack footprint into account might be inefficient. The footprint is only used for checking feasibility.

Definition at line 58 of file robot_footprint_model.h.


Constructor & Destructor Documentation

Default constructor of the abstract obstacle class.

Definition at line 65 of file robot_footprint_model.h.

Virtual destructor.

Definition at line 72 of file robot_footprint_model.h.


Member Function Documentation

virtual double teb_local_planner::BaseRobotFootprintModel::calculateDistance ( const PoseSE2 current_pose,
const Obstacle obstacle 
) const [pure virtual]

Calculate the distance between the robot and an obstacle.

Parameters:
current_poseCurrent robot pose
obstaclePointer to the obstacle
Returns:
Euclidean distance to the robot

Implemented in teb_local_planner::PolygonRobotFootprint, teb_local_planner::LineRobotFootprint, teb_local_planner::TwoCirclesRobotFootprint, teb_local_planner::CircularRobotFootprint, and teb_local_planner::PointRobotFootprint.

virtual void teb_local_planner::BaseRobotFootprintModel::visualizeRobot ( const PoseSE2 current_pose,
std::vector< visualization_msgs::Marker > &  markers 
) const [inline, virtual]

Visualize the robot using a markers.

Fill a marker message with all necessary information (type, pose, scale and color). The header, namespace, id and marker lifetime will be overwritten.

Parameters:
current_poseCurrent robot pose
[out]markerscontainer of marker messages describing the robot shape

Reimplemented in teb_local_planner::PolygonRobotFootprint, teb_local_planner::LineRobotFootprint, teb_local_planner::TwoCirclesRobotFootprint, and teb_local_planner::CircularRobotFootprint.

Definition at line 93 of file robot_footprint_model.h.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sat Jun 8 2019 20:21:34