Implements both nav_core::BaseLocalPlanner and mbf_costmap_core::CostmapController abstract interfaces, so the teb_local_planner plugin can be used both in move_base and move_base_flex (MBF).
More...
#include <mpc_local_planner_ros.h>
|
bool | cancel () |
| Requests the planner to cancel, e.g. if it takes too much time. More...
|
|
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...
|
|
uint32_t | computeVelocityCommands (const geometry_msgs::PoseStamped &pose, const geometry_msgs::TwistStamped &velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message) |
| Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base. More...
|
|
void | initialize (std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros) |
| Initializes the teb plugin. More...
|
|
bool | isGoalReached () |
| Check if the goal pose has been achieved. More...
|
|
bool | isGoalReached (double xy_tolerance, double yaw_tolerance) |
| Dummy version to satisfy MBF API. More...
|
|
| MpcLocalPlannerROS () |
| Default constructor of the plugin. More...
|
|
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
| Set the plan that the teb local planner is following. More...
|
|
| ~MpcLocalPlannerROS () |
| Destructor of the plugin. More...
|
|
virtual | ~BaseLocalPlanner () |
|
virtual void | initialize (std::string name, ::TF *tf, costmap_2d::Costmap2DROS *costmap_ros)=0 |
|
virtual | ~CostmapController () |
|
virtual | ~AbstractController () |
|
|
void | customObstacleCB (const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg) |
| Callback for the dynamic_reconfigure node. 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 geometry_msgs::PoseStamped &local_goal, int current_goal_idx, const geometry_msgs::TransformStamped &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 tf2_ros::Buffer &tf, const geometry_msgs::PoseStamped &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...
|
|
bool | transformGlobalPlan (const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const geometry_msgs::PoseStamped &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, geometry_msgs::TransformStamped *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...
|
|
| BaseLocalPlanner () |
|
| CostmapController () |
|
| AbstractController () |
|
Implements both nav_core::BaseLocalPlanner and mbf_costmap_core::CostmapController abstract interfaces, so the teb_local_planner plugin can be used both in move_base and move_base_flex (MBF).
- Todo:
- Escape behavior, more efficient obstacle handling
Definition at line 77 of file mpc_local_planner_ros.h.
◆ CircularObstacle
◆ LineObstacle
◆ ObstaclePtr
◆ ObstContainer
◆ Point2dContainer
◆ PointObstacle
◆ PolygonObstacle
◆ PoseSE2
◆ RobotFootprintModelPtr
◆ ViaPointContainer
◆ MpcLocalPlannerROS()
mpc_local_planner::MpcLocalPlannerROS::MpcLocalPlannerROS |
( |
| ) |
|
◆ ~MpcLocalPlannerROS()
mpc_local_planner::MpcLocalPlannerROS::~MpcLocalPlannerROS |
( |
| ) |
|
◆ cancel()
bool mpc_local_planner::MpcLocalPlannerROS::cancel |
( |
| ) |
|
|
inlinevirtual |
◆ computeVelocityCommands() [1/2]
bool mpc_local_planner::MpcLocalPlannerROS::computeVelocityCommands |
( |
geometry_msgs::Twist & |
cmd_vel | ) |
|
|
virtual |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
- Parameters
-
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
- Returns
- True if a valid trajectory was found, false otherwise
Implements nav_core::BaseLocalPlanner.
Definition at line 217 of file mpc_local_planner_ros.cpp.
◆ computeVelocityCommands() [2/2]
uint32_t mpc_local_planner::MpcLocalPlannerROS::computeVelocityCommands |
( |
const geometry_msgs::PoseStamped & |
pose, |
|
|
const geometry_msgs::TwistStamped & |
velocity, |
|
|
geometry_msgs::TwistStamped & |
cmd_vel, |
|
|
std::string & |
message |
|
) |
| |
|
virtual |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
- Parameters
-
pose | the current pose of the robot. |
velocity | the current velocity of the robot. |
cmd_vel | Will be filled with the velocity command to be passed to the robot base. |
message | Optional more detailed outcome as a string |
- Returns
- Result code as described on ExePath action result: SUCCESS = 0 1..9 are reserved as plugin specific non-error results FAILURE = 100 Unspecified failure, only used for old, non-mfb_core based plugins CANCELED = 101 NO_VALID_CMD = 102 PAT_EXCEEDED = 103 COLLISION = 104 OSCILLATION = 105 ROBOT_STUCK = 106 MISSED_GOAL = 107 MISSED_PATH = 108 BLOCKED_PATH = 109 INVALID_PATH = 110 TF_ERROR = 111 NOT_INITIALIZED = 112 INVALID_PLUGIN = 113 INTERNAL_ERROR = 114 121..149 are reserved as plugin specific errors
Implements mbf_costmap_core::CostmapController.
Definition at line 227 of file mpc_local_planner_ros.cpp.
◆ customObstacleCB()
void mpc_local_planner::MpcLocalPlannerROS::customObstacleCB |
( |
const costmap_converter::ObstacleArrayMsg::ConstPtr & |
obst_msg | ) |
|
|
protected |
Callback for the dynamic_reconfigure node.
This callback allows to modify parameters dynamically at runtime without restarting the node
- Parameters
-
config | Reference to the dynamic reconfigure config |
level | Dynamic reconfigure level 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 827 of file mpc_local_planner_ros.cpp.
◆ customViaPointsCB()
void mpc_local_planner::MpcLocalPlannerROS::customViaPointsCB |
( |
const nav_msgs::Path::ConstPtr & |
via_points_msg | ) |
|
|
protected |
Callback for custom via-points.
- Parameters
-
via_points_msg | pointer to the message containing a list of via-points |
Definition at line 833 of file mpc_local_planner_ros.cpp.
◆ estimateLocalGoalOrientation()
double mpc_local_planner::MpcLocalPlannerROS::estimateLocalGoalOrientation |
( |
const std::vector< geometry_msgs::PoseStamped > & |
global_plan, |
|
|
const geometry_msgs::PoseStamped & |
local_goal, |
|
|
int |
current_goal_idx, |
|
|
const geometry_msgs::TransformStamped & |
tf_plan_to_global, |
|
|
int |
moving_average_length = 3 |
|
) |
| const |
|
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.
- Parameters
-
| 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 |
- Returns
- orientation (yaw-angle) estimate
Definition at line 771 of file mpc_local_planner_ros.cpp.
◆ getNumberFromXMLRPC()
double mpc_local_planner::MpcLocalPlannerROS::getNumberFromXMLRPC |
( |
XmlRpc::XmlRpcValue & |
value, |
|
|
const std::string & |
full_param_name |
|
) |
| |
|
static |
Get a number from the given XmlRpcValue.
- Parameters
-
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. |
- Returns
- double value
Definition at line 1049 of file mpc_local_planner_ros.cpp.
◆ getRobotFootprintFromCostmap2d()
Get the current robot footprint/contour model.
- Parameters
-
costmap_ros | reference to an intialized instance of costmap_2d::Costmap2dROS |
- Returns
- Robot footprint model used for optimization
Definition at line 994 of file mpc_local_planner_ros.cpp.
◆ getRobotFootprintFromParamServer()
Get the current robot footprint/contour model.
- Parameters
-
nh | const reference to the local ros::NodeHandle |
costmap_ros | pointer to an intialized instance of costmap_2d::Costmap2dROS |
- Returns
- Robot footprint model used for optimization
Definition at line 854 of file mpc_local_planner_ros.cpp.
◆ initialize()
◆ isGoalReached() [1/2]
bool mpc_local_planner::MpcLocalPlannerROS::isGoalReached |
( |
| ) |
|
|
virtual |
◆ isGoalReached() [2/2]
bool mpc_local_planner::MpcLocalPlannerROS::isGoalReached |
( |
double |
xy_tolerance, |
|
|
double |
yaw_tolerance |
|
) |
| |
|
inlinevirtual |
◆ makeFootprintFromXMLRPC()
Set the footprint from the given XmlRpcValue.
- Parameters
-
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. |
- Returns
- container of vertices describing the polygon
Definition at line 1010 of file mpc_local_planner_ros.cpp.
◆ pruneGlobalPlan()
bool mpc_local_planner::MpcLocalPlannerROS::pruneGlobalPlan |
( |
const tf2_ros::Buffer & |
tf, |
|
|
const geometry_msgs::PoseStamped & |
global_pose, |
|
|
std::vector< geometry_msgs::PoseStamped > & |
global_plan, |
|
|
double |
dist_behind_robot = 1 |
|
) |
| |
|
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
.
- Parameters
-
| tf | A reference to a tf buffer |
| 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] |
- Returns
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 609 of file mpc_local_planner_ros.cpp.
◆ setPlan()
bool mpc_local_planner::MpcLocalPlannerROS::setPlan |
( |
const std::vector< geometry_msgs::PoseStamped > & |
orig_global_plan | ) |
|
|
virtual |
◆ tfPoseToEigenVector2dTransRot()
Eigen::Vector2d mpc_local_planner::MpcLocalPlannerROS::tfPoseToEigenVector2dTransRot |
( |
const tf::Pose & |
tf_vel | ) |
|
|
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).
- Parameters
-
tf_vel | tf::Pose message containing a 1D or 2D translational velocity (x,y) and an angular velocity (yaw-angle) |
- Returns
- Translational and angular velocity combined into an Eigen::Vector2d
Definition at line 601 of file mpc_local_planner_ros.cpp.
◆ transformGlobalPlan()
bool mpc_local_planner::MpcLocalPlannerROS::transformGlobalPlan |
( |
const tf2_ros::Buffer & |
tf, |
|
|
const std::vector< geometry_msgs::PoseStamped > & |
global_plan, |
|
|
const geometry_msgs::PoseStamped & |
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 , |
|
|
geometry_msgs::TransformStamped * |
tf_plan_to_global = NULL |
|
) |
| const |
|
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.
- Parameters
-
| tf | A reference to a tf buffer |
| 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 |
- Returns
true
if the global plan is transformed, false
otherwise
Definition at line 651 of file mpc_local_planner_ros.cpp.
◆ updateObstacleContainerWithCostmap()
void mpc_local_planner::MpcLocalPlannerROS::updateObstacleContainerWithCostmap |
( |
| ) |
|
|
protected |
◆ updateObstacleContainerWithCostmapConverter()
void mpc_local_planner::MpcLocalPlannerROS::updateObstacleContainerWithCostmapConverter |
( |
| ) |
|
|
protected |
◆ updateObstacleContainerWithCustomObstacles()
void mpc_local_planner::MpcLocalPlannerROS::updateObstacleContainerWithCustomObstacles |
( |
| ) |
|
|
protected |
◆ updateViaPointsContainer()
void mpc_local_planner::MpcLocalPlannerROS::updateViaPointsContainer |
( |
const std::vector< geometry_msgs::PoseStamped > & |
transformed_plan, |
|
|
double |
min_separation |
|
) |
| |
|
protected |
Update internal via-point container based on the current reference plan.
- Parameters
-
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 583 of file mpc_local_planner_ros.cpp.
◆ validateFootprints()
void mpc_local_planner::MpcLocalPlannerROS::validateFootprints |
( |
double |
opt_inscribed_radius, |
|
|
double |
costmap_inscribed_radius, |
|
|
double |
min_obst_dist |
|
) |
| |
|
protected |
Validate current parameter values of the footprint for optimization, obstacle distance and the costmap footprint.
This method prints warnings if validation fails.
- Parameters
-
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 818 of file mpc_local_planner_ros.cpp.
◆ _controller
Controller mpc_local_planner::MpcLocalPlannerROS::_controller |
|
private |
◆ _costmap
◆ _costmap_conv_params
◆ _costmap_converter
◆ _costmap_converter_loader
◆ _costmap_model
◆ _costmap_ros
◆ _custom_obst_mutex
std::mutex mpc_local_planner::MpcLocalPlannerROS::_custom_obst_mutex |
|
private |
◆ _custom_obst_sub
◆ _custom_obstacle_msg
costmap_converter::ObstacleArrayMsg mpc_local_planner::MpcLocalPlannerROS::_custom_obstacle_msg |
|
private |
◆ _custom_via_points_active
bool mpc_local_planner::MpcLocalPlannerROS::_custom_via_points_active = false |
|
private |
Keep track whether valid via-points have been received from via_points_sub_.
Definition at line 384 of file mpc_local_planner_ros.h.
◆ _footprint_spec
◆ _global_frame
std::string mpc_local_planner::MpcLocalPlannerROS::_global_frame |
|
private |
◆ _global_plan
std::vector<geometry_msgs::PoseStamped> mpc_local_planner::MpcLocalPlannerROS::_global_plan |
|
private |
◆ _goal_reached
bool mpc_local_planner::MpcLocalPlannerROS::_goal_reached = false |
|
private |
◆ _initialized
bool mpc_local_planner::MpcLocalPlannerROS::_initialized |
|
private |
◆ _last_cmd
◆ _no_infeasible_plans
int mpc_local_planner::MpcLocalPlannerROS::_no_infeasible_plans = 0 |
|
private |
◆ _obstacles
Obstacle vector that should be considered during local trajectory optimization.
Definition at line 362 of file mpc_local_planner_ros.h.
◆ _odom_helper
◆ _params
◆ _publisher
Publisher mpc_local_planner::MpcLocalPlannerROS::_publisher |
|
private |
◆ _robot_base_frame
std::string mpc_local_planner::MpcLocalPlannerROS::_robot_base_frame |
|
private |
◆ _robot_circumscribed_radius
double mpc_local_planner::MpcLocalPlannerROS::_robot_circumscribed_radius |
|
private |
◆ _robot_goal
PoseSE2 mpc_local_planner::MpcLocalPlannerROS::_robot_goal |
|
private |
◆ _robot_inscribed_radius
double mpc_local_planner::MpcLocalPlannerROS::_robot_inscribed_radius |
|
private |
◆ _robot_model
◆ _robot_pose
PoseSE2 mpc_local_planner::MpcLocalPlannerROS::_robot_pose |
|
private |
◆ _robot_vel
◆ _tf
◆ _time_last_cmd
ros::Time mpc_local_planner::MpcLocalPlannerROS::_time_last_cmd |
|
private |
◆ _time_last_infeasible_plan
ros::Time mpc_local_planner::MpcLocalPlannerROS::_time_last_infeasible_plan |
|
private |
◆ _u_seq
◆ _via_point_mutex
std::mutex mpc_local_planner::MpcLocalPlannerROS::_via_point_mutex |
|
private |
◆ _via_points
◆ _via_points_sub
◆ _x_seq
The documentation for this class was generated from the following files: