Go to the documentation of this file.
23 #ifndef MPC_LOCAL_PLANNER_ROS_H_
24 #define MPC_LOCAL_PLANNER_ROS_H_
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>
64 #include <boost/shared_ptr.hpp>
114 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
150 uint32_t
computeVelocityCommands(
const geometry_msgs::PoseStamped& pose,
const geometry_msgs::TwistStamped& velocity,
151 geometry_msgs::TwistStamped& cmd_vel, std::string& message);
172 bool cancel() {
return false; };
258 void updateViaPointsContainer(
const std::vector<geometry_msgs::PoseStamped>& transformed_plan,
double min_separation);
273 void customObstacleCB(
const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg);
297 std::vector<geometry_msgs::PoseStamped>& global_plan,
double dist_behind_robot = 1);
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;
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;
350 void validateFootprints(
double opt_inscribed_radius,
double costmap_inscribed_radius,
double min_obst_dist);
440 #endif // MPC_LOCAL_PLANNER_ROS_H_
teb_local_planner::PolygonObstacle PolygonObstacle
~MpcLocalPlannerROS()
Destructor of the plugin.
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
teb_local_planner::CircularObstacle CircularObstacle
double _robot_circumscribed_radius
The radius of the circumscribed circle of the robot.
teb_local_planner::PointObstacle PointObstacle
bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
std::string _robot_base_frame
Used as the base frame id of the robot.
static RobotFootprintModelPtr getRobotFootprintFromCostmap2d(costmap_2d::Costmap2DROS &costmap_ros)
Get the current robot footprint/contour model.
std::vector< geometry_msgs::PoseStamped > _global_plan
Store the current global plan.
static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose &tf_vel)
Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities.
RobotFootprintModelPtr _robot_model
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.
corbo::TimeSeries::Ptr _u_seq
teb_local_planner::PoseSE2 PoseSE2
ObstContainer _obstacles
Obstacle vector that should be considered during local trajectory optimization.
std::vector< geometry_msgs::Point > _footprint_spec
Store the footprint of the robot.
geometry_msgs::Twist _last_cmd
Store the last control command generated in computeVelocityCommands()
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the teb local planner is following.
bool _custom_via_points_active
Keep track whether valid via-points have been received from via_points_sub_.
std::mutex _via_point_mutex
Mutex that locks the via_points container (multi-threaded)
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
ros::Subscriber _via_points_sub
Subscriber for custom via-points received via a Path msg.
std::string _global_frame
The frame in which the controller will run.
void updateObstacleContainerWithCostmap()
Update internal obstacle vector based on occupied costmap cells.
geometry_msgs::Twist _robot_vel
Store current robot translational and angular velocity (vx, vy, omega)
bool global_plan_overwrite_orientation
bool _initialized
Keeps track about the correct initialization of this class.
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
struct mpc_local_planner::MpcLocalPlannerROS::Parameters _params
tf2_ros::Buffer * _tf
pointer to tf buffer
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > _costmap_converter
Store the current costmap_converter.
double costmap_converter_rate
bool is_footprint_dynamic
std::mutex _custom_obst_mutex
Mutex that locks the obstacle array (multi-threaded)
ViaPointContainer _via_points
bool _goal_reached
store whether the goal is reached or not
ros::Subscriber _custom_obst_sub
Subscriber for custom obstacles received via a ObstacleMsg.
void updateObstacleContainerWithCostmapConverter()
Update internal obstacle vector based on polygons provided by a costmap_converter plugin.
boost::shared_ptr< Obstacle > ObstaclePtr
bool costmap_converter_spin_thread
void updateViaPointsContainer(const std::vector< geometry_msgs::PoseStamped > &transformed_plan, double min_separation)
Update internal via-point container based on the current reference plan.
This class provides publishing methods for common messages.
double controller_frequency
double _robot_inscribed_radius
The radius of the inscribed circle of the robot (collision possible)
std::vector< ObstaclePtr > ObstContainer
PoseSE2 _robot_goal
Store current robot goal.
costmap_2d::Costmap2DROS * _costmap_ros
Pointer to the costmap ros wrapper, received from the navigation stack.
std::vector< PoseSE2 > ViaPointContainer
ros::Time _time_last_infeasible_plan
Store at which time stamp the last infeasible plan was detected.
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the teb plugin.
struct mpc_local_planner::MpcLocalPlannerROS::CostmapConverterPlugin _costmap_conv_params
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
costmap_converter::ObstacleArrayMsg _custom_obstacle_msg
Copy of the most recent obstacle message.
teb_local_planner::ObstContainer ObstContainer
bool isGoalReached()
Check if the goal pose has been achieved.
corbo::TimeSeries::Ptr _x_seq
double costmap_obstacles_behind_robot_dist
void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg)
Callback for the dynamic_reconfigure node.
static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue &value, const std::string &full_param_name)
Get a number from the given XmlRpcValue.
std::string costmap_converter_plugin
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).
PoseSE2 _robot_pose
Store current robot pose.
costmap_2d::Costmap2D * _costmap
Pointer to the 2d costmap (obtained from the costmap ros wrapper)
bool include_costmap_obstacles
double global_plan_viapoint_sep
double collision_check_min_resolution_angular
double max_global_plan_lookahead_dist
void customViaPointsCB(const nav_msgs::Path::ConstPtr &via_points_msg)
Callback for custom via-points.
static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle &nh, costmap_2d::Costmap2DROS *costmap_ros=nullptr)
Get the current robot footprint/contour model.
double global_plan_prune_distance
int collision_check_no_poses
int _no_infeasible_plans
Store how many times in a row the planner failed to find a feasible plan.
MpcLocalPlannerROS()
Default constructor of the plugin.
std::shared_ptr< TimeSeries > Ptr
void updateObstacleContainerWithCustomObstacles()
Update internal obstacle vector based on custom messages received via subscriber.
teb_local_planner::Point2dContainer Point2dContainer
std::shared_ptr< base_local_planner::CostmapModel > _costmap_model
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name)
Set the footprint from the given XmlRpcValue.
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > _costmap_converter_loader
Load costmap converter plugins at runtime.
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...
base_local_planner::OdometryHelperRos _odom_helper
Provides an interface to receive the current velocity from the robot.
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...
MPC controller for mobile robots.
double yaw_goal_tolerance
teb_local_planner::LineObstacle LineObstacle
mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06