Class that approximates the robot with line segment (zero-width) More...
#include <robot_footprint_model.h>
Public Member Functions | |
virtual double | calculateDistance (const PoseSE2 ¤t_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 ¤t_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_ |
Class that approximates the robot with line segment (zero-width)
Definition at line 345 of file robot_footprint_model.h.
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.
line_start | start coordinates (only x and y) of the line (w.r.t. robot center at (0,0)) |
line_end | end 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)
line_start | start coordinates (only x and y) of the line (w.r.t. robot center at (0,0)) |
line_end | end 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 teb_local_planner::LineRobotFootprint::~LineRobotFootprint | ( | ) | [inline, virtual] |
Virtual destructor.
Definition at line 372 of file robot_footprint_model.h.
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.
current_pose | Current robot pose |
obstacle | Pointer to the obstacle |
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.
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.
vertices | footprint 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)
vertices | footprint 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.
current_pose | Current robot pose | |
[out] | markers | container of marker messages describing the robot shape |
Reimplemented from teb_local_planner::BaseRobotFootprintModel.
Definition at line 424 of file robot_footprint_model.h.
Eigen::Vector2d teb_local_planner::LineRobotFootprint::line_end_ [private] |
Definition at line 466 of file robot_footprint_model.h.
Eigen::Vector2d teb_local_planner::LineRobotFootprint::line_start_ [private] |
Definition at line 465 of file robot_footprint_model.h.