Public Member Functions | Private Attributes | List of all members
teb_local_planner::CircularRobotFootprint Class Reference

Class that defines the a robot of circular shape. More...

#include <robot_footprint_model.h>

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

Public Member Functions

virtual double calculateDistance (const PoseSE2 &current_pose, const Obstacle *obstacle) const
 Calculate the distance between the robot and an obstacle. More...
 
 CircularRobotFootprint (double radius)
 Default constructor of the abstract obstacle class. More...
 
virtual double estimateSpatioTemporalDistance (const PoseSE2 &current_pose, const Obstacle *obstacle, double t) const
 Estimate the distance between the robot and the predicted location of an obstacle at time t. More...
 
virtual double getInscribedRadius ()
 Compute the inscribed radius of the footprint model. More...
 
void setRadius (double radius)
 Set radius of the circular robot. 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 ~CircularRobotFootprint ()
 Virtual destructor. More...
 
- Public Member Functions inherited from teb_local_planner::BaseRobotFootprintModel
 BaseRobotFootprintModel ()
 Default constructor of the abstract obstacle class. More...
 
virtual ~BaseRobotFootprintModel ()
 Virtual destructor. More...
 

Private Attributes

double radius_
 

Detailed Description

Class that defines the a robot of circular shape.

Definition at line 184 of file robot_footprint_model.h.

Constructor & Destructor Documentation

teb_local_planner::CircularRobotFootprint::CircularRobotFootprint ( double  radius)
inline

Default constructor of the abstract obstacle class.

Parameters
radiusradius of the robot

Definition at line 192 of file robot_footprint_model.h.

virtual teb_local_planner::CircularRobotFootprint::~CircularRobotFootprint ( )
inlinevirtual

Virtual destructor.

Definition at line 197 of file robot_footprint_model.h.

Member Function Documentation

virtual double teb_local_planner::CircularRobotFootprint::calculateDistance ( const PoseSE2 current_pose,
const Obstacle obstacle 
) const
inlinevirtual

Calculate the distance between the robot and an obstacle.

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

Implements teb_local_planner::BaseRobotFootprintModel.

Definition at line 211 of file robot_footprint_model.h.

virtual double teb_local_planner::CircularRobotFootprint::estimateSpatioTemporalDistance ( const PoseSE2 current_pose,
const Obstacle obstacle,
double  t 
) const
inlinevirtual

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

Implements teb_local_planner::BaseRobotFootprintModel.

Definition at line 223 of file robot_footprint_model.h.

virtual double teb_local_planner::CircularRobotFootprint::getInscribedRadius ( )
inlinevirtual

Compute the inscribed radius of the footprint model.

Returns
inscribed radius

Implements teb_local_planner::BaseRobotFootprintModel.

Definition at line 252 of file robot_footprint_model.h.

void teb_local_planner::CircularRobotFootprint::setRadius ( double  radius)
inline

Set radius of the circular robot.

Parameters
radiusradius of the robot

Definition at line 203 of file robot_footprint_model.h.

virtual void teb_local_planner::CircularRobotFootprint::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 from teb_local_planner::BaseRobotFootprintModel.

Definition at line 237 of file robot_footprint_model.h.

Member Data Documentation

double teb_local_planner::CircularRobotFootprint::radius_
private

Definition at line 256 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