Class that approximates the robot with line segment (zero-width)
More...
#include <robot_footprint_model.h>
|
virtual double | calculateDistance (const PoseSE2 ¤t_pose, const Obstacle *obstacle) const |
| Calculate the distance between the robot and an obstacle. More...
|
|
virtual double | estimateSpatioTemporalDistance (const PoseSE2 ¤t_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 Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, const double min_obstacle_dist) |
| Default constructor of the abstract obstacle class (Eigen Version) More...
|
|
| LineRobotFootprint (const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end) |
| Default constructor of the abstract obstacle class. More...
|
|
void | setLine (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end) |
| Set vertices of the contour/footprint (Eigen version) More...
|
|
void | setLine (const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end) |
| Set vertices of the contour/footprint. More...
|
|
virtual void | visualizeRobot (const PoseSE2 ¤t_pose, std::vector< visualization_msgs::Marker > &markers, const std_msgs::ColorRGBA &color) const |
| Visualize the robot using a markers. More...
|
|
virtual | ~LineRobotFootprint () |
| Virtual destructor. More...
|
|
|
void | transformToWorld (const PoseSE2 ¤t_pose, Eigen::Vector2d &line_start_world, Eigen::Vector2d &line_end_world) const |
| Transforms a line to the world frame manually. More...
|
|
Class that approximates the robot with line segment (zero-width)
Definition at line 475 of file robot_footprint_model.h.
◆ LineRobotFootprint() [1/2]
Default constructor of the abstract obstacle class.
- Parameters
-
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 484 of file robot_footprint_model.h.
◆ LineRobotFootprint() [2/2]
teb_local_planner::LineRobotFootprint::LineRobotFootprint |
( |
const Eigen::Vector2d & |
line_start, |
|
|
const Eigen::Vector2d & |
line_end, |
|
|
const double |
min_obstacle_dist |
|
) |
| |
|
inline |
Default constructor of the abstract obstacle class (Eigen Version)
- Parameters
-
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 494 of file robot_footprint_model.h.
◆ ~LineRobotFootprint()
virtual teb_local_planner::LineRobotFootprint::~LineRobotFootprint |
( |
| ) |
|
|
inlinevirtual |
◆ calculateDistance()
virtual double teb_local_planner::LineRobotFootprint::calculateDistance |
( |
const PoseSE2 & |
current_pose, |
|
|
const Obstacle * |
obstacle |
|
) |
| const |
|
inlinevirtual |
◆ estimateSpatioTemporalDistance()
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_pose | robot pose, from which the distance to the obstacle is estimated |
obstacle | Pointer to the dynamic obstacle (constant velocity model is assumed) |
t | time, for which the predicted distance to the obstacle is calculated |
- Returns
- Euclidean distance to the robot
Implements teb_local_planner::BaseRobotFootprintModel.
Definition at line 547 of file robot_footprint_model.h.
◆ getInscribedRadius()
virtual double teb_local_planner::LineRobotFootprint::getInscribedRadius |
( |
| ) |
|
|
inlinevirtual |
◆ setLine() [1/2]
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
-
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 520 of file robot_footprint_model.h.
◆ setLine() [2/2]
Set vertices of the contour/footprint.
- Parameters
-
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 508 of file robot_footprint_model.h.
◆ transformToWorld()
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_pose | Current robot pose |
[out] | line_start | line_start_ in the world frame |
[out] | line_end | line_end_ in the world frame |
Definition at line 646 of file robot_footprint_model.h.
◆ visualizeRobot()
virtual void teb_local_planner::LineRobotFootprint::visualizeRobot |
( |
const PoseSE2 & |
current_pose, |
|
|
std::vector< visualization_msgs::Marker > & |
markers, |
|
|
const std_msgs::ColorRGBA & |
color |
|
) |
| 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_pose | Current robot pose |
[out] | markers | container of marker messages describing the robot shape |
| color | Color of the footprint |
Reimplemented from teb_local_planner::BaseRobotFootprintModel.
Definition at line 564 of file robot_footprint_model.h.
◆ line_end_
Eigen::Vector2d teb_local_planner::LineRobotFootprint::line_end_ |
|
private |
◆ line_start_
Eigen::Vector2d teb_local_planner::LineRobotFootprint::line_start_ |
|
private |
◆ min_obstacle_dist_
const double teb_local_planner::LineRobotFootprint::min_obstacle_dist_ = 0.0 |
|
private |
The documentation for this class was generated from the following file: