Public Member Functions | Private Attributes
teb_local_planner::PolygonRobotFootprint Class Reference

Class that approximates the robot with a closed polygon. More...

#include <robot_footprint_model.h>

Inheritance diagram for teb_local_planner::PolygonRobotFootprint:
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.
 PolygonRobotFootprint (const Point2dContainer &vertices)
 Default constructor of the abstract obstacle class.
void setVertices (const Point2dContainer &vertices)
 Set vertices of the contour/footprint.
virtual void visualizeRobot (const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
 Visualize the robot using a markers.
virtual ~PolygonRobotFootprint ()
 Virtual destructor.

Private Attributes

Point2dContainer vertices_

Detailed Description

Class that approximates the robot with a closed polygon.

Definition at line 440 of file robot_footprint_model.h.


Constructor & Destructor Documentation

Default constructor of the abstract obstacle class.

Parameters:
verticesfootprint vertices (only x and y) around the robot center (0,0) (do not repeat the first and last vertex at the end)

Definition at line 450 of file robot_footprint_model.h.

Virtual destructor.

Definition at line 455 of file robot_footprint_model.h.


Member Function Documentation

virtual double teb_local_planner::PolygonRobotFootprint::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 469 of file robot_footprint_model.h.

Set vertices of the contour/footprint.

Parameters:
verticesfootprint vertices (only x and y) around the robot center (0,0) (do not repeat the first and last vertex at the end)

Definition at line 461 of file robot_footprint_model.h.

virtual void teb_local_planner::PolygonRobotFootprint::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 491 of file robot_footprint_model.h.


Member Data Documentation

Definition at line 529 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:16