Public Member Functions | List of all members
teb_local_planner::BaseRobotFootprintModel Class Referenceabstract

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]

Public Member Functions

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

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

teb_local_planner::BaseRobotFootprintModel::BaseRobotFootprintModel ( )
inline

Default constructor of the abstract obstacle class.

Definition at line 65 of file robot_footprint_model.h.

virtual teb_local_planner::BaseRobotFootprintModel::~BaseRobotFootprintModel ( )
inlinevirtual

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 double teb_local_planner::BaseRobotFootprintModel::estimateSpatioTemporalDistance ( const PoseSE2 current_pose,
const Obstacle obstacle,
double  t 
) const
pure virtual

Estimate the distance between the robot and the predicted location of an obstacle at time t.

Parameters
current_poserobot pose, from which the distance to the obstacle is estimated
obstaclePointer to the dynamic obstacle (constant velocity model is assumed)
ttime, for which the predicted distance to the obstacle is calculated
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 double teb_local_planner::BaseRobotFootprintModel::getInscribedRadius ( )
pure virtual
virtual void teb_local_planner::BaseRobotFootprintModel::visualizeRobot ( const PoseSE2 current_pose,
std::vector< visualization_msgs::Marker > &  markers,
const std_msgs::ColorRGBA &  color 
) const
inlinevirtual

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
colorColor of the footprint

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

Definition at line 103 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 Wed Jun 3 2020 04:03:08