Implements the actual abstract navigation stack routines of the teb_local_planner plugin. More...
#include <teb_local_planner_ros.h>
Public Member Functions | |
bool | computeVelocityCommands (geometry_msgs::Twist &cmd_vel) |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base. More... | |
void | initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) |
Initializes the teb plugin. More... | |
bool | isGoalReached () |
Check if the goal pose has been achieved. More... | |
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
Set the plan that the teb local planner is following. More... | |
TebLocalPlannerROS () | |
Default constructor of the teb plugin. More... | |
~TebLocalPlannerROS () | |
Destructor of the plugin. More... | |
Public Member Functions inherited from nav_core::BaseLocalPlanner | |
virtual | ~BaseLocalPlanner () |
Static Public Member Functions | |
Public utility functions/methods | |
static Eigen::Vector2d | tfPoseToEigenVector2dTransRot (const tf::Pose &tf_vel) |
Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities. More... | |
static RobotFootprintModelPtr | getRobotFootprintFromParamServer (const ros::NodeHandle &nh) |
Get the current robot footprint/contour model. More... | |
static Point2dContainer | makeFootprintFromXMLRPC (XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name) |
Set the footprint from the given XmlRpcValue. More... | |
static double | getNumberFromXMLRPC (XmlRpc::XmlRpcValue &value, const std::string &full_param_name) |
Get a number from the given XmlRpcValue. More... | |
Protected Member Functions | |
void | configureBackupModes (std::vector< geometry_msgs::PoseStamped > &transformed_plan, int &goal_idx) |
double | convertTransRotVelToSteeringAngle (double v, double omega, double wheelbase, double min_turning_radius=0) const |
Convert translational and rotational velocities to a steering angle of a carlike robot. More... | |
void | customObstacleCB (const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg) |
Callback for custom obstacles that are not obtained from the costmap. More... | |
void | customViaPointsCB (const nav_msgs::Path::ConstPtr &via_points_msg) |
Callback for custom via-points. More... | |
double | estimateLocalGoalOrientation (const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &local_goal, int current_goal_idx, const tf::StampedTransform &tf_plan_to_global, int moving_average_length=3) const |
Estimate the orientation of a pose from the global_plan that is treated as a local goal for the local planner. More... | |
bool | pruneGlobalPlan (const tf::TransformListener &tf, const tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &global_plan, double dist_behind_robot=1) |
Prune global plan such that already passed poses are cut off. More... | |
void | reconfigureCB (TebLocalPlannerReconfigureConfig &config, uint32_t level) |
Callback for the dynamic_reconfigure node. More... | |
void | saturateVelocity (double &vx, double &vy, double &omega, double max_vel_x, double max_vel_y, double max_vel_theta, double max_vel_x_backwards) const |
Saturate the translational and angular velocity to given limits. More... | |
bool | transformGlobalPlan (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &global_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, double max_plan_length, std::vector< geometry_msgs::PoseStamped > &transformed_plan, int *current_goal_idx=NULL, tf::StampedTransform *tf_plan_to_global=NULL) const |
Transforms the global plan of the robot from the planner frame to the local frame (modified). More... | |
void | updateObstacleContainerWithCostmap () |
Update internal obstacle vector based on occupied costmap cells. More... | |
void | updateObstacleContainerWithCostmapConverter () |
Update internal obstacle vector based on polygons provided by a costmap_converter plugin. More... | |
void | updateObstacleContainerWithCustomObstacles () |
Update internal obstacle vector based on custom messages received via subscriber. More... | |
void | updateViaPointsContainer (const std::vector< geometry_msgs::PoseStamped > &transformed_plan, double min_separation) |
Update internal via-point container based on the current reference plan. More... | |
void | validateFootprints (double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist) |
Validate current parameter values of the footprint for optimization, obstacle distance and the costmap footprint. More... | |
Protected Member Functions inherited from nav_core::BaseLocalPlanner | |
BaseLocalPlanner () | |
Private Attributes | |
TebConfig | cfg_ |
Config class that stores and manages all related parameters. More... | |
costmap_2d::Costmap2D * | costmap_ |
Pointer to the 2d costmap (obtained from the costmap ros wrapper) More... | |
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > | costmap_converter_ |
Store the current costmap_converter. More... | |
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > | costmap_converter_loader_ |
Load costmap converter plugins at runtime. More... | |
boost::shared_ptr< base_local_planner::CostmapModel > | costmap_model_ |
costmap_2d::Costmap2DROS * | costmap_ros_ |
Pointer to the costmap ros wrapper, received from the navigation stack. More... | |
boost::mutex | custom_obst_mutex_ |
Mutex that locks the obstacle array (multi-threaded) More... | |
ros::Subscriber | custom_obst_sub_ |
Subscriber for custom obstacles received via a ObstacleMsg. More... | |
costmap_converter::ObstacleArrayMsg | custom_obstacle_msg_ |
Copy of the most recent obstacle message. More... | |
bool | custom_via_points_active_ |
Keep track whether valid via-points have been received from via_points_sub_. More... | |
boost::shared_ptr< dynamic_reconfigure::Server< TebLocalPlannerReconfigureConfig > > | dynamic_recfg_ |
Dynamic reconfigure server to allow config modifications at runtime. More... | |
FailureDetector | failure_detector_ |
Detect if the robot got stucked. More... | |
std::vector< geometry_msgs::Point > | footprint_spec_ |
Store the footprint of the robot. More... | |
std::string | global_frame_ |
The frame in which the controller will run. More... | |
std::vector< geometry_msgs::PoseStamped > | global_plan_ |
Store the current global plan. More... | |
bool | goal_reached_ |
store whether the goal is reached or not More... | |
bool | initialized_ |
Keeps track about the correct initialization of this class. More... | |
geometry_msgs::Twist | last_cmd_ |
Store the last control command generated in computeVelocityCommands() More... | |
RotType | last_preferred_rotdir_ |
Store recent preferred turning direction. More... | |
int | no_infeasible_plans_ |
Store how many times in a row the planner failed to find a feasible plan. More... | |
ObstContainer | obstacles_ |
Obstacle vector that should be considered during local trajectory optimization. More... | |
base_local_planner::OdometryHelperRos | odom_helper_ |
Provides an interface to receive the current velocity from the robot. More... | |
PlannerInterfacePtr | planner_ |
Instance of the underlying optimal planner class. More... | |
std::string | robot_base_frame_ |
Used as the base frame id of the robot. More... | |
double | robot_circumscribed_radius |
The radius of the circumscribed circle of the robot. More... | |
PoseSE2 | robot_goal_ |
Store current robot goal. More... | |
double | robot_inscribed_radius_ |
The radius of the inscribed circle of the robot (collision possible) More... | |
PoseSE2 | robot_pose_ |
Store current robot pose. More... | |
geometry_msgs::Twist | robot_vel_ |
Store current robot translational and angular velocity (vx, vy, omega) More... | |
tf::TransformListener * | tf_ |
pointer to Transform Listener More... | |
ros::Time | time_last_infeasible_plan_ |
Store at which time stamp the last infeasible plan was detected. More... | |
ros::Time | time_last_oscillation_ |
Store at which time stamp the last oscillation was detected. More... | |
boost::mutex | via_point_mutex_ |
Mutex that locks the via_points container (multi-threaded) More... | |
ViaPointContainer | via_points_ |
Container of via-points that should be considered during local trajectory optimization. More... | |
ros::Subscriber | via_points_sub_ |
Subscriber for custom via-points received via a Path msg. More... | |
TebVisualizationPtr | visualization_ |
Instance of the visualization class (local/global plan, obstacles, ...) More... | |
Implements the actual abstract navigation stack routines of the teb_local_planner plugin.
Definition at line 92 of file teb_local_planner_ros.h.
teb_local_planner::TebLocalPlannerROS::TebLocalPlannerROS | ( | ) |
Default constructor of the teb plugin.
Definition at line 64 of file teb_local_planner_ros.cpp.
teb_local_planner::TebLocalPlannerROS::~TebLocalPlannerROS | ( | ) |
Destructor of the plugin.
Definition at line 72 of file teb_local_planner_ros.cpp.
|
virtual |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
Implements nav_core::BaseLocalPlanner.
Definition at line 213 of file teb_local_planner_ros.cpp.
|
protected |
Definition at line 885 of file teb_local_planner_ros.cpp.
|
protected |
Convert translational and rotational velocities to a steering angle of a carlike robot.
The conversion is based on the following equations:
v | translational velocity [m/s] |
omega | rotational velocity [rad/s] |
wheelbase | distance between both axles (drive shaft and steering axle), the value might be negative for back_wheeled robots |
min_turning_radius | Specify a lower bound on the turning radius |
Definition at line 861 of file teb_local_planner_ros.cpp.
|
protected |
Callback for custom obstacles that are not obtained from the costmap.
obst_msg | pointer to the message containing a list of polygon shaped obstacles |
Definition at line 960 of file teb_local_planner_ros.cpp.
|
protected |
Callback for custom via-points.
via_points_msg | pointer to the message containing a list of via-points |
Definition at line 966 of file teb_local_planner_ros.cpp.
|
protected |
Estimate the orientation of a pose from the global_plan that is treated as a local goal for the local planner.
If the current (local) goal point is not the final one (global) substitute the goal orientation by the angle of the direction vector between the local goal and the subsequent pose of the global plan. This is often helpful, if the global planner does not consider orientations.
A moving average filter is utilized to smooth the orientation.
global_plan | The global plan | |
local_goal | Current local goal | |
current_goal_idx | Index of the current (local) goal pose in the global plan | |
[out] | tf_plan_to_global | Transformation between the global plan and the global planning frame |
moving_average_length | number of future poses of the global plan to be taken into account |
Definition at line 787 of file teb_local_planner_ros.cpp.
|
static |
Get a number from the given XmlRpcValue.
value | double value type |
full_param_name | this is the full name of the rosparam from which the footprint_xmlrpc value came. It is used only for reporting errors. |
Definition at line 1145 of file teb_local_planner_ros.cpp.
|
static |
Get the current robot footprint/contour model.
nh | const reference to the local ros::NodeHandle |
Definition at line 986 of file teb_local_planner_ros.cpp.
|
virtual |
Initializes the teb plugin.
name | The name of the instance |
tf | Pointer to a transform listener |
costmap_ros | Cost map representing occupied and free space |
Implements nav_core::BaseLocalPlanner.
Definition at line 81 of file teb_local_planner_ros.cpp.
|
virtual |
Check if the goal pose has been achieved.
The actual check is performed in computeVelocityCommands(). Only the status flag is checked here.
Implements nav_core::BaseLocalPlanner.
Definition at line 410 of file teb_local_planner_ros.cpp.
|
static |
Set the footprint from the given XmlRpcValue.
footprint_xmlrpc | should be an array of arrays, where the top-level array should have 3 or more elements, and the sub-arrays should all have exactly 2 elements (x and y coordinates). |
full_param_name | this is the full name of the rosparam from which the footprint_xmlrpc value came. It is used only for reporting errors. |
Definition at line 1108 of file teb_local_planner_ros.cpp.
|
protected |
Prune global plan such that already passed poses are cut off.
The pose of the robot is transformed into the frame of the global plan by taking the most recent tf transform. If no valid transformation can be found, the method returns false
. The global plan is pruned until the distance to the robot is at least dist_behind_robot
. If no pose within the specified treshold dist_behind_robot
can be found, nothing will be pruned and the method returns false
.
dist_behind_robot
too small (not smaller the cellsize of the map), otherwise nothing will be pruned. tf | A reference to a transform listener | |
global_pose | The global pose of the robot | |
[in,out] | global_plan | The plan to be transformed |
dist_behind_robot | Distance behind the robot that should be kept [meters] |
true
if the plan is pruned, false
in case of a transform exception or if no pose cannot be found inside the threshold Definition at line 606 of file teb_local_planner_ros.cpp.
|
protected |
Callback for the dynamic_reconfigure node.
This callback allows to modify parameters dynamically at runtime without restarting the node
config | Reference to the dynamic reconfigure config |
level | Dynamic reconfigure level |
Definition at line 76 of file teb_local_planner_ros.cpp.
|
protected |
Saturate the translational and angular velocity to given limits.
The limit of the translational velocity for backwards driving can be changed independently. Do not choose max_vel_x_backwards <= 0. If no backward driving is desired, change the optimization weight for penalizing backwards driving instead.
[in,out] | vx | The translational velocity that should be saturated. |
[in,out] | vy | Strafing velocity which can be nonzero for holonomic robots |
[in,out] | omega | The angular velocity that should be saturated. |
max_vel_x | Maximum translational velocity for forward driving | |
max_vel_y | Maximum strafing velocity (for holonomic robots) | |
max_vel_theta | Maximum (absolute) angular velocity | |
max_vel_x_backwards | Maximum translational velocity for backwards driving |
Definition at line 833 of file teb_local_planner_ros.cpp.
|
virtual |
Set the plan that the teb local planner is following.
orig_global_plan | The plan to pass to the local planner |
Implements nav_core::BaseLocalPlanner.
Definition at line 190 of file teb_local_planner_ros.cpp.
|
static |
Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities.
Translational velocities (x- and y-coordinates) are combined into a single translational velocity (first component).
tf_vel | tf::Pose message containing a 1D or 2D translational velocity (x,y) and an angular velocity (yaw-angle) |
Definition at line 597 of file teb_local_planner_ros.cpp.
|
protected |
Transforms the global plan of the robot from the planner frame to the local frame (modified).
The method replaces transformGlobalPlan as defined in base_local_planner/goal_functions.h such that the index of the current goal pose is returned as well as the transformation between the global plan and the planning frame.
tf | A reference to a transform listener | |
global_plan | The plan to be transformed | |
global_pose | The global pose of the robot | |
costmap | A reference to the costmap being used so the window size for transforming can be computed | |
global_frame | The frame to transform the plan to | |
max_plan_length | Specify maximum length (cumulative Euclidean distances) of the transformed plan [if <=0: disabled; the length is also bounded by the local costmap size!] | |
[out] | transformed_plan | Populated with the transformed plan |
[out] | current_goal_idx | Index of the current (local) goal pose in the global plan |
[out] | tf_plan_to_global | Transformation between the global plan and the global planning frame |
true
if the global plan is transformed, false
otherwise Definition at line 651 of file teb_local_planner_ros.cpp.
|
protected |
Update internal obstacle vector based on occupied costmap cells.
Include temporal coherence among obstacle msgs (id vector)
Include properties for dynamic obstacles (e.g. using constant velocity model)
Definition at line 423 of file teb_local_planner_ros.cpp.
|
protected |
Update internal obstacle vector based on polygons provided by a costmap_converter plugin.
Definition at line 451 of file teb_local_planner_ros.cpp.
|
protected |
Update internal obstacle vector based on custom messages received via subscriber.
Definition at line 497 of file teb_local_planner_ros.cpp.
|
protected |
Update internal via-point container based on the current reference plan.
transformed_plan | (local) portion of the global plan (which is already transformed to the planning frame) |
min_separation | minimum separation between two consecutive via-points |
Definition at line 576 of file teb_local_planner_ros.cpp.
|
protected |
Validate current parameter values of the footprint for optimization, obstacle distance and the costmap footprint.
This method prints warnings if validation fails.
opt_inscribed_radius | Inscribed radius of the RobotFootprintModel for optimization |
costmap_inscribed_radius | Inscribed radius of the footprint model used for the costmap |
min_obst_dist | desired distance to obstacles |
Definition at line 875 of file teb_local_planner_ros.cpp.
|
private |
Config class that stores and manages all related parameters.
Definition at line 365 of file teb_local_planner_ros.h.
|
private |
Pointer to the 2d costmap (obtained from the costmap ros wrapper)
Definition at line 356 of file teb_local_planner_ros.h.
|
private |
Store the current costmap_converter.
Definition at line 373 of file teb_local_planner_ros.h.
|
private |
Load costmap converter plugins at runtime.
Definition at line 372 of file teb_local_planner_ros.h.
|
private |
Definition at line 364 of file teb_local_planner_ros.h.
|
private |
Pointer to the costmap ros wrapper, received from the navigation stack.
Definition at line 355 of file teb_local_planner_ros.h.
|
private |
Mutex that locks the obstacle array (multi-threaded)
Definition at line 377 of file teb_local_planner_ros.h.
|
private |
Subscriber for custom obstacles received via a ObstacleMsg.
Definition at line 376 of file teb_local_planner_ros.h.
|
private |
Copy of the most recent obstacle message.
Definition at line 378 of file teb_local_planner_ros.h.
|
private |
Keep track whether valid via-points have been received from via_points_sub_.
Definition at line 381 of file teb_local_planner_ros.h.
|
private |
Dynamic reconfigure server to allow config modifications at runtime.
Definition at line 375 of file teb_local_planner_ros.h.
|
private |
Detect if the robot got stucked.
Definition at line 366 of file teb_local_planner_ros.h.
|
private |
Store the footprint of the robot.
Definition at line 394 of file teb_local_planner_ros.h.
|
private |
The frame in which the controller will run.
Definition at line 398 of file teb_local_planner_ros.h.
|
private |
Store the current global plan.
Definition at line 368 of file teb_local_planner_ros.h.
|
private |
store whether the goal is reached or not
Definition at line 387 of file teb_local_planner_ros.h.
|
private |
Keeps track about the correct initialization of this class.
Definition at line 402 of file teb_local_planner_ros.h.
|
private |
Store the last control command generated in computeVelocityCommands()
Definition at line 392 of file teb_local_planner_ros.h.
|
private |
Store recent preferred turning direction.
Definition at line 391 of file teb_local_planner_ros.h.
|
private |
Store how many times in a row the planner failed to find a feasible plan.
Definition at line 389 of file teb_local_planner_ros.h.
|
private |
Obstacle vector that should be considered during local trajectory optimization.
Definition at line 361 of file teb_local_planner_ros.h.
|
private |
Provides an interface to receive the current velocity from the robot.
Definition at line 370 of file teb_local_planner_ros.h.
|
private |
Instance of the underlying optimal planner class.
Definition at line 360 of file teb_local_planner_ros.h.
|
private |
Used as the base frame id of the robot.
Definition at line 399 of file teb_local_planner_ros.h.
|
private |
The radius of the circumscribed circle of the robot.
Definition at line 396 of file teb_local_planner_ros.h.
|
private |
Store current robot goal.
Definition at line 385 of file teb_local_planner_ros.h.
|
private |
The radius of the inscribed circle of the robot (collision possible)
Definition at line 395 of file teb_local_planner_ros.h.
|
private |
Store current robot pose.
Definition at line 384 of file teb_local_planner_ros.h.
|
private |
Store current robot translational and angular velocity (vx, vy, omega)
Definition at line 386 of file teb_local_planner_ros.h.
|
private |
pointer to Transform Listener
Definition at line 357 of file teb_local_planner_ros.h.
|
private |
Store at which time stamp the last infeasible plan was detected.
Definition at line 388 of file teb_local_planner_ros.h.
|
private |
Store at which time stamp the last oscillation was detected.
Definition at line 390 of file teb_local_planner_ros.h.
|
private |
Mutex that locks the via_points container (multi-threaded)
Definition at line 382 of file teb_local_planner_ros.h.
|
private |
Container of via-points that should be considered during local trajectory optimization.
Definition at line 362 of file teb_local_planner_ros.h.
|
private |
Subscriber for custom via-points received via a Path msg.
Definition at line 380 of file teb_local_planner_ros.h.
|
private |
Instance of the visualization class (local/global plan, obstacles, ...)
Definition at line 363 of file teb_local_planner_ros.h.