Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef TEB_LOCAL_PLANNER_ROS_H_
00040 #define TEB_LOCAL_PLANNER_ROS_H_
00041
00042 #include <ros/ros.h>
00043
00044
00045 #include <nav_core/base_local_planner.h>
00046 #include <base_local_planner/goal_functions.h>
00047 #include <base_local_planner/odometry_helper_ros.h>
00048 #include <base_local_planner/costmap_model.h>
00049
00050
00051
00052 #include <teb_local_planner/optimal_planner.h>
00053 #include <teb_local_planner/homotopy_class_planner.h>
00054 #include <teb_local_planner/visualization.h>
00055
00056
00057 #include <nav_msgs/Path.h>
00058 #include <nav_msgs/Odometry.h>
00059 #include <geometry_msgs/PoseStamped.h>
00060 #include <visualization_msgs/MarkerArray.h>
00061 #include <visualization_msgs/Marker.h>
00062 #include <teb_local_planner/ObstacleMsg.h>
00063
00064
00065 #include <angles/angles.h>
00066 #include <tf/tf.h>
00067 #include <tf/transform_listener.h>
00068 #include <tf/transform_datatypes.h>
00069
00070
00071 #include <costmap_2d/costmap_2d_ros.h>
00072 #include <costmap_converter/costmap_converter_interface.h>
00073
00074
00075
00076 #include <teb_local_planner/TebLocalPlannerReconfigureConfig.h>
00077 #include <dynamic_reconfigure/server.h>
00078
00079
00080 #include <boost/bind.hpp>
00081 #include <boost/shared_ptr.hpp>
00082
00083
00084 namespace teb_local_planner
00085 {
00086
00092 class TebLocalPlannerROS : public nav_core::BaseLocalPlanner
00093 {
00094
00095 public:
00099 TebLocalPlannerROS();
00100
00104 ~TebLocalPlannerROS();
00105
00112 void initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros);
00113
00119 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
00120
00126 bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
00127
00135 bool isGoalReached();
00136
00137
00138
00141
00149 static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel);
00150
00156 static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle& nh);
00157
00168 static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, const std::string& full_param_name);
00169
00179 static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name);
00180
00182
00183 protected:
00184
00193 void updateObstacleContainerWithCostmap();
00194
00201 void updateObstacleContainerWithCostmapConverter();
00202
00208 void updateObstacleContainerWithCustomObstacles();
00209
00210
00217 void updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation);
00218
00219
00227 void reconfigureCB(TebLocalPlannerReconfigureConfig& config, uint32_t level);
00228
00229
00234 void customObstacleCB(const teb_local_planner::ObstacleMsg::ConstPtr& obst_msg);
00235
00236
00252 bool pruneGlobalPlan(const tf::TransformListener& tf, const tf::Stamped<tf::Pose>& global_pose,
00253 std::vector<geometry_msgs::PoseStamped>& global_plan, double dist_behind_robot=1);
00254
00272 bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
00273 const tf::Stamped<tf::Pose>& global_pose, const costmap_2d::Costmap2D& costmap,
00274 const std::string& global_frame, double max_plan_length, std::vector<geometry_msgs::PoseStamped>& transformed_plan,
00275 int* current_goal_idx = NULL, tf::StampedTransform* tf_plan_to_global = NULL) const;
00276
00292 double estimateLocalGoalOrientation(const std::vector<geometry_msgs::PoseStamped>& global_plan, const tf::Stamped<tf::Pose>& local_goal,
00293 int current_goal_idx, const tf::StampedTransform& tf_plan_to_global, int moving_average_length=3) const;
00294
00295
00308 void saturateVelocity(double& v, double& omega, double max_vel_x, double max_vel_theta, double max_vel_x_backwards) const;
00309
00310
00325 double convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius = 0) const;
00326
00327
00328
00329
00330
00331 private:
00332
00333
00334
00335 costmap_2d::Costmap2DROS* costmap_ros_;
00336 costmap_2d::Costmap2D* costmap_;
00337 tf::TransformListener* tf_;
00338
00339
00340 PlannerInterfacePtr planner_;
00341 ObstContainer obstacles_;
00342 ViaPointContainer via_points_;
00343 TebVisualizationPtr visualization_;
00344 boost::shared_ptr<base_local_planner::CostmapModel> costmap_model_;
00345 TebConfig cfg_;
00346
00347 std::vector<geometry_msgs::PoseStamped> global_plan_;
00348
00349 base_local_planner::OdometryHelperRos odom_helper_;
00350
00351 pluginlib::ClassLoader<costmap_converter::BaseCostmapToPolygons> costmap_converter_loader_;
00352 boost::shared_ptr<costmap_converter::BaseCostmapToPolygons> costmap_converter_;
00353
00354 boost::shared_ptr< dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig> > dynamic_recfg_;
00355 ros::Subscriber custom_obst_sub_;
00356 boost::mutex custom_obst_mutex_;
00357 ObstacleMsg custom_obstacle_msg_;
00358
00359 PoseSE2 robot_pose_;
00360 PoseSE2 robot_goal_;
00361 Eigen::Vector2d robot_vel_;
00362 bool goal_reached_;
00363 bool horizon_reduced_;
00364 ros::Time horizon_reduced_stamp_;
00365
00366 std::vector<geometry_msgs::Point> footprint_spec_;
00367 double robot_inscribed_radius_;
00368 double robot_circumscribed_radius;
00369
00370 std::string global_frame_;
00371 std::string robot_base_frame_;
00372
00373
00374 bool initialized_;
00375
00376 public:
00377 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00378 };
00379
00380 };
00381
00382 #endif // TEB_LOCAL_PLANNER_ROS_H_
00383
00384