Public Member Functions | Private Attributes
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]

List of all members.

Public Member Functions

virtual double calculateDistance (const PoseSE2 &current_pose, const Obstacle *obstacle) const
 Calculate the distance between the robot and an obstacle.
 CircularRobotFootprint (double radius)
 Default constructor of the abstract obstacle class.
void setRadius (double radius)
 Set radius of the circular robot.
virtual void visualizeRobot (const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
 Visualize the robot using a markers.
virtual ~CircularRobotFootprint ()
 Virtual destructor.

Private Attributes

double radius_

Detailed Description

Class that defines the a robot of circular shape.

Definition at line 149 of file robot_footprint_model.h.


Constructor & Destructor Documentation

Default constructor of the abstract obstacle class.

Parameters:
radiusradius of the robot

Definition at line 157 of file robot_footprint_model.h.

Virtual destructor.

Definition at line 162 of file robot_footprint_model.h.


Member Function Documentation

virtual double teb_local_planner::CircularRobotFootprint::calculateDistance ( const PoseSE2 current_pose,
const Obstacle obstacle 
) const [inline, 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

Implements teb_local_planner::BaseRobotFootprintModel.

Definition at line 176 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 168 of file robot_footprint_model.h.

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

Definition at line 189 of file robot_footprint_model.h.


Member Data Documentation

Definition at line 205 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 Mon Oct 24 2016 05:31:15