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

Class that approximates the robot with line segment (zero-width) More...

#include <robot_footprint_model.h>

Inheritance diagram for teb_local_planner::LineRobotFootprint:
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.
virtual double getInscribedRadius ()
 Compute the inscribed radius of the footprint model.
 LineRobotFootprint (const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end)
 Default constructor of the abstract obstacle class.
 LineRobotFootprint (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end)
 Default constructor of the abstract obstacle class (Eigen Version)
void setLine (const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end)
 Set vertices of the contour/footprint.
void setLine (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end)
 Set vertices of the contour/footprint (Eigen version)
virtual void visualizeRobot (const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
 Visualize the robot using a markers.
virtual ~LineRobotFootprint ()
 Virtual destructor.

Private Attributes

Eigen::Vector2d line_end_
Eigen::Vector2d line_start_

Detailed Description

Class that approximates the robot with line segment (zero-width)

Definition at line 345 of file robot_footprint_model.h.


Constructor & Destructor Documentation

Default constructor of the abstract obstacle class.

Parameters:
line_startstart coordinates (only x and y) of the line (w.r.t. robot center at (0,0))
line_endend coordinates (only x and y) of the line (w.r.t. robot center at (0,0))

Definition at line 354 of file robot_footprint_model.h.

teb_local_planner::LineRobotFootprint::LineRobotFootprint ( const Eigen::Vector2d &  line_start,
const Eigen::Vector2d &  line_end 
) [inline]

Default constructor of the abstract obstacle class (Eigen Version)

Parameters:
line_startstart coordinates (only x and y) of the line (w.r.t. robot center at (0,0))
line_endend coordinates (only x and y) of the line (w.r.t. robot center at (0,0))

Definition at line 364 of file robot_footprint_model.h.

Virtual destructor.

Definition at line 372 of file robot_footprint_model.h.


Member Function Documentation

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

virtual double teb_local_planner::LineRobotFootprint::getInscribedRadius ( ) [inline, virtual]

Compute the inscribed radius of the footprint model.

Returns:
inscribed radius

Implements teb_local_planner::BaseRobotFootprintModel.

Definition at line 458 of file robot_footprint_model.h.

void teb_local_planner::LineRobotFootprint::setLine ( const geometry_msgs::Point line_start,
const geometry_msgs::Point line_end 
) [inline]

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 378 of file robot_footprint_model.h.

void teb_local_planner::LineRobotFootprint::setLine ( const Eigen::Vector2d &  line_start,
const Eigen::Vector2d &  line_end 
) [inline]

Set vertices of the contour/footprint (Eigen version)

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 390 of file robot_footprint_model.h.

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


Member Data Documentation

Definition at line 466 of file robot_footprint_model.h.

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