mpc_local_planner_ros.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020, Christoph Rösmann, All rights reserved.
6  *
7  * This program is free software: you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation, either version 3 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <https://www.gnu.org/licenses/>.
19  *
20  * Authors: Christoph Rösmann
21  *********************************************************************/
22 
23 #ifndef MPC_LOCAL_PLANNER_ROS_H_
24 #define MPC_LOCAL_PLANNER_ROS_H_
25 
26 #include <ros/ros.h>
27 
28 // base local planner base class and utilities
34 
35 // mpc_local_planner related classes
38 
39 // teb_local_planner related classes
43 
44 // message types
45 #include <costmap_converter/ObstacleMsg.h>
46 #include <geometry_msgs/PoseStamped.h>
47 #include <nav_msgs/Odometry.h>
48 #include <nav_msgs/Path.h>
49 #include <visualization_msgs/Marker.h>
50 #include <visualization_msgs/MarkerArray.h>
51 
52 // transforms
53 #include <tf2/utils.h>
54 #include <tf2_ros/buffer.h>
55 
56 // costmap
59 
60 // dynamic reconfigure
61 // #include <dynamic_reconfigure/server.h>
62 // #include <mpc_local_planner/MpcLocalPlannerReconfigureConfig.h>
63 
64 #include <boost/shared_ptr.hpp>
65 
66 #include <memory>
67 #include <mutex>
68 
69 namespace mpc_local_planner {
70 
77 class MpcLocalPlannerROS : public nav_core::BaseLocalPlanner, public mbf_costmap_core::CostmapController
78 {
83  using ViaPointContainer = std::vector<PoseSE2>;
84 
90 
91  public:
100 
107  void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros);
108 
114  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
115 
121  bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
122 
150  uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped& pose, const geometry_msgs::TwistStamped& velocity,
151  geometry_msgs::TwistStamped& cmd_vel, std::string& message);
152 
160  bool isGoalReached();
161 
165  bool isGoalReached(double xy_tolerance, double yaw_tolerance) { return isGoalReached(); };
166 
172  bool cancel() { return false; };
173 
176 
184  static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel);
185 
193 
200 
211  static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, const std::string& full_param_name);
212 
222  static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name);
223 
225 
226  protected:
236 
244 
251 
258  void updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation);
259 
267  // void reconfigureCB(MpcLocalPlannerReconfigureConfig& config, uint32_t level);
268 
273  void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg);
274 
279  void customViaPointsCB(const nav_msgs::Path::ConstPtr& via_points_msg);
280 
296  bool pruneGlobalPlan(const tf2_ros::Buffer& tf, const geometry_msgs::PoseStamped& global_pose,
297  std::vector<geometry_msgs::PoseStamped>& global_plan, double dist_behind_robot = 1);
298 
317  bool transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
318  const geometry_msgs::PoseStamped& global_pose, const costmap_2d::Costmap2D& costmap, const std::string& global_frame,
319  double max_plan_length, std::vector<geometry_msgs::PoseStamped>& transformed_plan, int* current_goal_idx = NULL,
320  geometry_msgs::TransformStamped* tf_plan_to_global = NULL) const;
321 
337  double estimateLocalGoalOrientation(const std::vector<geometry_msgs::PoseStamped>& global_plan, const geometry_msgs::PoseStamped& local_goal,
338  int current_goal_idx, const geometry_msgs::TransformStamped& tf_plan_to_global,
339  int moving_average_length = 3) const;
340 
350  void validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist);
351 
352  private:
353  // Definition of member variables
354 
355  // external objects (store weak pointers)
359 
360  // internal objects
364  std::shared_ptr<base_local_planner::CostmapModel> _costmap_model;
365 
366  corbo::TimeSeries::Ptr _x_seq = std::make_shared<corbo::TimeSeries>();
367  corbo::TimeSeries::Ptr _u_seq = std::make_shared<corbo::TimeSeries>();
368 
369  std::vector<geometry_msgs::PoseStamped> _global_plan;
370 
372 
375 
376  // std::shared_ptr<dynamic_reconfigure::Server<MpcLocalPlannerReconfigureConfig>>
377  // dynamic_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime
379  std::mutex _custom_obst_mutex;
380  costmap_converter::ObstacleArrayMsg _custom_obstacle_msg;
381 
385  std::mutex _via_point_mutex;
386 
389  geometry_msgs::Twist _robot_vel;
390  bool _goal_reached = false;
392  int _no_infeasible_plans = 0;
393  geometry_msgs::Twist _last_cmd;
395 
397 
398  std::vector<geometry_msgs::Point> _footprint_spec;
401 
402  std::string _global_frame;
403  std::string _robot_base_frame;
404 
405  // flags
406  bool _initialized;
407 
408  struct Parameters
409  {
410  double xy_goal_tolerance = 0.2;
411  double yaw_goal_tolerance = 0.1;
415  bool is_footprint_dynamic = false;
421  std::string odom_topic = "odom";
422  double controller_frequency = 10;
423 
424  } _params;
425 
427  {
429  double costmap_converter_rate = 5;
431 
433 
434  public:
436 };
437 
438 }; // end namespace mpc_local_planner
439 
440 #endif // MPC_LOCAL_PLANNER_ROS_H_
mbf_costmap_core::CostmapController
mpc_local_planner::MpcLocalPlannerROS::_controller
Controller _controller
Definition: mpc_local_planner_ros.h:381
mpc_local_planner::MpcLocalPlannerROS::CostmapConverterPlugin
Definition: mpc_local_planner_ros.h:446
mpc_local_planner::MpcLocalPlannerROS::PolygonObstacle
teb_local_planner::PolygonObstacle PolygonObstacle
Definition: mpc_local_planner_ros.h:109
mpc_local_planner::MpcLocalPlannerROS::~MpcLocalPlannerROS
~MpcLocalPlannerROS()
Destructor of the plugin.
Definition: mpc_local_planner_ros.cpp:77
teb_local_planner::RobotFootprintModelPtr
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
mpc_local_planner::MpcLocalPlannerROS::CircularObstacle
teb_local_planner::CircularObstacle CircularObstacle
Definition: mpc_local_planner_ros.h:107
mpc_local_planner::MpcLocalPlannerROS::_robot_circumscribed_radius
double _robot_circumscribed_radius
The radius of the circumscribed circle of the robot.
Definition: mpc_local_planner_ros.h:420
mpc_local_planner::MpcLocalPlannerROS::PointObstacle
teb_local_planner::PointObstacle PointObstacle
Definition: mpc_local_planner_ros.h:106
mpc_local_planner::MpcLocalPlannerROS::cancel
bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
Definition: mpc_local_planner_ros.h:192
mpc_local_planner::MpcLocalPlannerROS::_robot_base_frame
std::string _robot_base_frame
Used as the base frame id of the robot.
Definition: mpc_local_planner_ros.h:423
mpc_local_planner::MpcLocalPlannerROS::getRobotFootprintFromCostmap2d
static RobotFootprintModelPtr getRobotFootprintFromCostmap2d(costmap_2d::Costmap2DROS &costmap_ros)
Get the current robot footprint/contour model.
Definition: mpc_local_planner_ros.cpp:1014
mpc_local_planner::MpcLocalPlannerROS::_global_plan
std::vector< geometry_msgs::PoseStamped > _global_plan
Store the current global plan.
Definition: mpc_local_planner_ros.h:389
mpc_local_planner::MpcLocalPlannerROS::tfPoseToEigenVector2dTransRot
static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose &tf_vel)
Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities.
Definition: mpc_local_planner_ros.cpp:621
boost::shared_ptr< BaseRobotFootprintModel >
mpc_local_planner::MpcLocalPlannerROS::_robot_model
RobotFootprintModelPtr _robot_model
Definition: mpc_local_planner_ros.h:416
utils.h
mpc_local_planner::MpcLocalPlannerROS::pruneGlobalPlan
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.
Definition: mpc_local_planner_ros.cpp:629
mpc_local_planner::MpcLocalPlannerROS::_u_seq
corbo::TimeSeries::Ptr _u_seq
Definition: mpc_local_planner_ros.h:387
ros.h
mpc_local_planner::MpcLocalPlannerROS::_publisher
Publisher _publisher
Definition: mpc_local_planner_ros.h:383
mpc_local_planner::MpcLocalPlannerROS::PoseSE2
teb_local_planner::PoseSE2 PoseSE2
Definition: mpc_local_planner_ros.h:99
mpc_local_planner::MpcLocalPlannerROS::_obstacles
ObstContainer _obstacles
Obstacle vector that should be considered during local trajectory optimization.
Definition: mpc_local_planner_ros.h:382
mpc_local_planner::MpcLocalPlannerROS::_footprint_spec
std::vector< geometry_msgs::Point > _footprint_spec
Store the footprint of the robot.
Definition: mpc_local_planner_ros.h:418
mpc_local_planner::MpcLocalPlannerROS::_last_cmd
geometry_msgs::Twist _last_cmd
Store the last control command generated in computeVelocityCommands()
Definition: mpc_local_planner_ros.h:413
mpc_local_planner::MpcLocalPlannerROS::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the teb local planner is following.
Definition: mpc_local_planner_ros.cpp:215
mpc_local_planner::MpcLocalPlannerROS::_custom_via_points_active
bool _custom_via_points_active
Keep track whether valid via-points have been received from via_points_sub_.
Definition: mpc_local_planner_ros.h:404
mpc_local_planner::MpcLocalPlannerROS::_via_point_mutex
std::mutex _via_point_mutex
Mutex that locks the via_points container (multi-threaded)
Definition: mpc_local_planner_ros.h:405
Point2dContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
mpc_local_planner::MpcLocalPlannerROS::_via_points_sub
ros::Subscriber _via_points_sub
Subscriber for custom via-points received via a Path msg.
Definition: mpc_local_planner_ros.h:403
goal_functions.h
mpc_local_planner::MpcLocalPlannerROS::_global_frame
std::string _global_frame
The frame in which the controller will run.
Definition: mpc_local_planner_ros.h:422
mpc_local_planner::MpcLocalPlannerROS::updateObstacleContainerWithCostmap
void updateObstacleContainerWithCostmap()
Update internal obstacle vector based on occupied costmap cells.
Definition: mpc_local_planner_ros.cpp:458
mpc_local_planner::MpcLocalPlannerROS::_robot_vel
geometry_msgs::Twist _robot_vel
Store current robot translational and angular velocity (vx, vy, omega)
Definition: mpc_local_planner_ros.h:409
buffer.h
mpc_local_planner::MpcLocalPlannerROS::Parameters::odom_topic
std::string odom_topic
Definition: mpc_local_planner_ros.h:441
mpc_local_planner::MpcLocalPlannerROS::Parameters::global_plan_overwrite_orientation
bool global_plan_overwrite_orientation
Definition: mpc_local_planner_ros.h:432
costmap_2d::Costmap2D
mpc_local_planner::MpcLocalPlannerROS::_initialized
bool _initialized
Keeps track about the correct initialization of this class.
Definition: mpc_local_planner_ros.h:426
controller.h
mpc_local_planner::MpcLocalPlannerROS::computeVelocityCommands
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
Definition: mpc_local_planner_ros.cpp:237
mpc_local_planner::MpcLocalPlannerROS::_params
struct mpc_local_planner::MpcLocalPlannerROS::Parameters _params
mpc_local_planner::MpcLocalPlannerROS::_tf
tf2_ros::Buffer * _tf
pointer to tf buffer
Definition: mpc_local_planner_ros.h:378
mpc_local_planner::MpcLocalPlannerROS::_costmap_converter
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > _costmap_converter
Store the current costmap_converter.
Definition: mpc_local_planner_ros.h:394
costmap_2d_ros.h
mpc_local_planner::MpcLocalPlannerROS::CostmapConverterPlugin::costmap_converter_rate
double costmap_converter_rate
Definition: mpc_local_planner_ros.h:449
mpc_local_planner
Definition: controller.h:44
mpc_local_planner::MpcLocalPlannerROS::Parameters::is_footprint_dynamic
bool is_footprint_dynamic
Definition: mpc_local_planner_ros.h:435
mpc_local_planner::MpcLocalPlannerROS::_custom_obst_mutex
std::mutex _custom_obst_mutex
Mutex that locks the obstacle array (multi-threaded)
Definition: mpc_local_planner_ros.h:399
mpc_local_planner::MpcLocalPlannerROS::_via_points
ViaPointContainer _via_points
Definition: mpc_local_planner_ros.h:402
mpc_local_planner::MpcLocalPlannerROS::_goal_reached
bool _goal_reached
store whether the goal is reached or not
Definition: mpc_local_planner_ros.h:410
mpc_local_planner::MpcLocalPlannerROS::_custom_obst_sub
ros::Subscriber _custom_obst_sub
Subscriber for custom obstacles received via a ObstacleMsg.
Definition: mpc_local_planner_ros.h:398
base_local_planner.h
mpc_local_planner::MpcLocalPlannerROS::updateObstacleContainerWithCostmapConverter
void updateObstacleContainerWithCostmapConverter()
Update internal obstacle vector based on polygons provided by a costmap_converter plugin.
Definition: mpc_local_planner_ros.cpp:485
teb_local_planner::ObstaclePtr
boost::shared_ptr< Obstacle > ObstaclePtr
mpc_local_planner::MpcLocalPlannerROS::CostmapConverterPlugin::costmap_converter_spin_thread
bool costmap_converter_spin_thread
Definition: mpc_local_planner_ros.h:450
mpc_local_planner::MpcLocalPlannerROS::updateViaPointsContainer
void updateViaPointsContainer(const std::vector< geometry_msgs::PoseStamped > &transformed_plan, double min_separation)
Update internal via-point container based on the current reference plan.
Definition: mpc_local_planner_ros.cpp:603
mpc_local_planner::Publisher
This class provides publishing methods for common messages.
Definition: publisher.h:66
teb_local_planner::CircularObstacle
mpc_local_planner::MpcLocalPlannerROS::Parameters::xy_goal_tolerance
double xy_goal_tolerance
Definition: mpc_local_planner_ros.h:430
mpc_local_planner::MpcLocalPlannerROS::Parameters::controller_frequency
double controller_frequency
Definition: mpc_local_planner_ros.h:442
mpc_local_planner::MpcLocalPlannerROS::_robot_inscribed_radius
double _robot_inscribed_radius
The radius of the inscribed circle of the robot (collision possible)
Definition: mpc_local_planner_ros.h:419
costmap_model.h
ObstContainer
std::vector< ObstaclePtr > ObstContainer
mpc_local_planner::MpcLocalPlannerROS::_robot_goal
PoseSE2 _robot_goal
Store current robot goal.
Definition: mpc_local_planner_ros.h:408
robot_footprint_model.h
mpc_local_planner::MpcLocalPlannerROS::_costmap_ros
costmap_2d::Costmap2DROS * _costmap_ros
Pointer to the costmap ros wrapper, received from the navigation stack.
Definition: mpc_local_planner_ros.h:376
base_local_planner::OdometryHelperRos
mpc_local_planner::MpcLocalPlannerROS::ViaPointContainer
std::vector< PoseSE2 > ViaPointContainer
Definition: mpc_local_planner_ros.h:103
mpc_local_planner::MpcLocalPlannerROS::_time_last_infeasible_plan
ros::Time _time_last_infeasible_plan
Store at which time stamp the last infeasible plan was detected.
Definition: mpc_local_planner_ros.h:411
tf2_ros::Buffer
mpc_local_planner::MpcLocalPlannerROS::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the teb plugin.
Definition: mpc_local_planner_ros.cpp:86
mpc_local_planner::MpcLocalPlannerROS::_costmap_conv_params
struct mpc_local_planner::MpcLocalPlannerROS::CostmapConverterPlugin _costmap_conv_params
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
pose_se2.h
mpc_local_planner::MpcLocalPlannerROS::_custom_obstacle_msg
costmap_converter::ObstacleArrayMsg _custom_obstacle_msg
Copy of the most recent obstacle message.
Definition: mpc_local_planner_ros.h:400
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons >
publisher.h
tf::Transform
mpc_local_planner::MpcLocalPlannerROS::ObstContainer
teb_local_planner::ObstContainer ObstContainer
Definition: mpc_local_planner_ros.h:102
mpc_local_planner::MpcLocalPlannerROS::isGoalReached
bool isGoalReached()
Check if the goal pose has been achieved.
Definition: mpc_local_planner_ros.cpp:447
mpc_local_planner::MpcLocalPlannerROS::_x_seq
corbo::TimeSeries::Ptr _x_seq
Definition: mpc_local_planner_ros.h:386
mpc_local_planner::MpcLocalPlannerROS::Parameters::costmap_obstacles_behind_robot_dist
double costmap_obstacles_behind_robot_dist
Definition: mpc_local_planner_ros.h:437
mpc_local_planner::MpcLocalPlannerROS::customObstacleCB
void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg)
Callback for the dynamic_reconfigure node.
Definition: mpc_local_planner_ros.cpp:847
mpc_local_planner::MpcLocalPlannerROS::getNumberFromXMLRPC
static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue &value, const std::string &full_param_name)
Get a number from the given XmlRpcValue.
Definition: mpc_local_planner_ros.cpp:1069
teb_local_planner::PointObstacle
mpc_local_planner::MpcLocalPlannerROS::CostmapConverterPlugin::costmap_converter_plugin
std::string costmap_converter_plugin
Definition: mpc_local_planner_ros.h:448
mpc_local_planner::MpcLocalPlannerROS::_time_last_cmd
ros::Time _time_last_cmd
Definition: mpc_local_planner_ros.h:414
mpc_local_planner::MpcLocalPlannerROS::transformGlobalPlan
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).
Definition: mpc_local_planner_ros.cpp:671
mpc_local_planner::MpcLocalPlannerROS::_robot_pose
PoseSE2 _robot_pose
Store current robot pose.
Definition: mpc_local_planner_ros.h:407
mpc_local_planner::MpcLocalPlannerROS::_costmap
costmap_2d::Costmap2D * _costmap
Pointer to the 2d costmap (obtained from the costmap ros wrapper)
Definition: mpc_local_planner_ros.h:377
mpc_local_planner::MpcLocalPlannerROS::Parameters
Definition: mpc_local_planner_ros.h:428
teb_local_planner::PoseSE2
mpc_local_planner::MpcLocalPlannerROS::Parameters::include_costmap_obstacles
bool include_costmap_obstacles
Definition: mpc_local_planner_ros.h:436
ros::Time
mpc_local_planner::MpcLocalPlannerROS::Parameters::global_plan_viapoint_sep
double global_plan_viapoint_sep
Definition: mpc_local_planner_ros.h:438
mpc_local_planner::MpcLocalPlannerROS::Parameters::collision_check_min_resolution_angular
double collision_check_min_resolution_angular
Definition: mpc_local_planner_ros.h:439
teb_local_planner::LineObstacle
mpc_local_planner::MpcLocalPlannerROS::Parameters::max_global_plan_lookahead_dist
double max_global_plan_lookahead_dist
Definition: mpc_local_planner_ros.h:434
mpc_local_planner::MpcLocalPlannerROS::customViaPointsCB
void customViaPointsCB(const nav_msgs::Path::ConstPtr &via_points_msg)
Callback for custom via-points.
Definition: mpc_local_planner_ros.cpp:853
mpc_local_planner::MpcLocalPlannerROS::getRobotFootprintFromParamServer
static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle &nh, costmap_2d::Costmap2DROS *costmap_ros=nullptr)
Get the current robot footprint/contour model.
Definition: mpc_local_planner_ros.cpp:874
mpc_local_planner::MpcLocalPlannerROS::Parameters::global_plan_prune_distance
double global_plan_prune_distance
Definition: mpc_local_planner_ros.h:433
mpc_local_planner::MpcLocalPlannerROS::Parameters::collision_check_no_poses
int collision_check_no_poses
Definition: mpc_local_planner_ros.h:440
mpc_local_planner::MpcLocalPlannerROS::_no_infeasible_plans
int _no_infeasible_plans
Store how many times in a row the planner failed to find a feasible plan.
Definition: mpc_local_planner_ros.h:412
mpc_local_planner::MpcLocalPlannerROS::MpcLocalPlannerROS
MpcLocalPlannerROS()
Default constructor of the plugin.
Definition: mpc_local_planner_ros.cpp:64
tf
costmap_controller.h
teb_local_planner::PolygonObstacle
costmap_converter_interface.h
obstacles.h
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
mpc_local_planner::MpcLocalPlannerROS::updateObstacleContainerWithCustomObstacles
void updateObstacleContainerWithCustomObstacles()
Update internal obstacle vector based on custom messages received via subscriber.
Definition: mpc_local_planner_ros.cpp:527
mpc_local_planner::MpcLocalPlannerROS::Point2dContainer
teb_local_planner::Point2dContainer Point2dContainer
Definition: mpc_local_planner_ros.h:101
mpc_local_planner::MpcLocalPlannerROS::_costmap_model
std::shared_ptr< base_local_planner::CostmapModel > _costmap_model
Definition: mpc_local_planner_ros.h:384
ViaPointContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
mpc_local_planner::MpcLocalPlannerROS::makeFootprintFromXMLRPC
static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name)
Set the footprint from the given XmlRpcValue.
Definition: mpc_local_planner_ros.cpp:1030
mpc_local_planner::MpcLocalPlannerROS::_costmap_converter_loader
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > _costmap_converter_loader
Load costmap converter plugins at runtime.
Definition: mpc_local_planner_ros.h:393
odometry_helper_ros.h
mpc_local_planner::MpcLocalPlannerROS::validateFootprints
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 costma...
Definition: mpc_local_planner_ros.cpp:838
costmap_2d::Costmap2DROS
mpc_local_planner::MpcLocalPlannerROS::_odom_helper
base_local_planner::OdometryHelperRos _odom_helper
Provides an interface to receive the current velocity from the robot.
Definition: mpc_local_planner_ros.h:391
XmlRpc::XmlRpcValue
nav_core::BaseLocalPlanner
mpc_local_planner::MpcLocalPlannerROS::estimateLocalGoalOrientation
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...
Definition: mpc_local_planner_ros.cpp:791
mpc_local_planner::Controller
MPC controller for mobile robots.
Definition: controller.h:73
ros::NodeHandle
ros::Subscriber
mpc_local_planner::MpcLocalPlannerROS::Parameters::yaw_goal_tolerance
double yaw_goal_tolerance
Definition: mpc_local_planner_ros.h:431
mpc_local_planner::MpcLocalPlannerROS::LineObstacle
teb_local_planner::LineObstacle LineObstacle
Definition: mpc_local_planner_ros.h:108


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06