Public Member Functions | Private Member Functions | Private Attributes | List of all members
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]

Public Member Functions

virtual double calculateDistance (const PoseSE2 &current_pose, const Obstacle *obstacle) const
 Calculate the distance between the robot and an obstacle. 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...
 
 LineRobotFootprint (const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end)
 Default constructor of the abstract obstacle class. More...
 
 LineRobotFootprint (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end)
 Default constructor of the abstract obstacle class (Eigen Version) More...
 
void setLine (const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end)
 Set vertices of the contour/footprint. More...
 
void setLine (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end)
 Set vertices of the contour/footprint (Eigen version) More...
 
virtual void visualizeRobot (const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
 Visualize the robot using a markers. More...
 
virtual ~LineRobotFootprint ()
 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 Member Functions

void transformToWorld (const PoseSE2 &current_pose, Eigen::Vector2d &line_start_world, Eigen::Vector2d &line_end_world) const
 Transforms a line to the world frame manually. More...
 

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

Constructor & Destructor Documentation

teb_local_planner::LineRobotFootprint::LineRobotFootprint ( const geometry_msgs::Point line_start,
const geometry_msgs::Point line_end 
)
inline

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

virtual teb_local_planner::LineRobotFootprint::~LineRobotFootprint ( )
inlinevirtual

Virtual destructor.

Definition at line 420 of file robot_footprint_model.h.

Member Function Documentation

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

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

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

Compute the inscribed radius of the footprint model.

Returns
inscribed radius

Implements teb_local_planner::BaseRobotFootprintModel.

Definition at line 515 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 426 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 438 of file robot_footprint_model.h.

void teb_local_planner::LineRobotFootprint::transformToWorld ( const PoseSE2 current_pose,
Eigen::Vector2d &  line_start_world,
Eigen::Vector2d &  line_end_world 
) const
inlineprivate

Transforms a line to the world frame manually.

Parameters
current_poseCurrent robot pose
[out]line_startline_start_ in the world frame
[out]line_endline_end_ in the world frame

Definition at line 528 of file robot_footprint_model.h.

virtual void teb_local_planner::LineRobotFootprint::visualizeRobot ( const PoseSE2 current_pose,
std::vector< visualization_msgs::Marker > &  markers 
) 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

Reimplemented from teb_local_planner::BaseRobotFootprintModel.

Definition at line 481 of file robot_footprint_model.h.

Member Data Documentation

Eigen::Vector2d teb_local_planner::LineRobotFootprint::line_end_
private

Definition at line 539 of file robot_footprint_model.h.

Eigen::Vector2d teb_local_planner::LineRobotFootprint::line_start_
private

Definition at line 538 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 5 2019 19:25:10