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 OPTIMAL_PLANNER_H_
00040 #define OPTIMAL_PLANNER_H_
00041
00042 #include <math.h>
00043
00044
00045
00046 #include <teb_local_planner/teb_config.h>
00047 #include <teb_local_planner/misc.h>
00048 #include <teb_local_planner/timed_elastic_band.h>
00049 #include <teb_local_planner/planner_interface.h>
00050 #include <teb_local_planner/visualization.h>
00051 #include <teb_local_planner/robot_footprint_model.h>
00052
00053
00054 #include "g2o/core/sparse_optimizer.h"
00055 #include "g2o/core/block_solver.h"
00056 #include "g2o/core/factory.h"
00057 #include "g2o/core/optimization_algorithm_gauss_newton.h"
00058 #include "g2o/core/optimization_algorithm_levenberg.h"
00059 #include "g2o/solvers/csparse/linear_solver_csparse.h"
00060 #include "g2o/solvers/cholmod/linear_solver_cholmod.h"
00061
00062
00063 #include <teb_local_planner/g2o_types/edge_velocity.h>
00064 #include <teb_local_planner/g2o_types/edge_acceleration.h>
00065 #include <teb_local_planner/g2o_types/edge_kinematics.h>
00066 #include <teb_local_planner/g2o_types/edge_time_optimal.h>
00067 #include <teb_local_planner/g2o_types/edge_obstacle.h>
00068 #include <teb_local_planner/g2o_types/edge_dynamic_obstacle.h>
00069 #include <teb_local_planner/g2o_types/edge_via_point.h>
00070
00071
00072 #include <nav_msgs/Path.h>
00073 #include <geometry_msgs/PoseStamped.h>
00074 #include <tf/transform_datatypes.h>
00075 #include <teb_local_planner/TrajectoryMsg.h>
00076
00077 #include <nav_msgs/Odometry.h>
00078 #include <limits.h>
00079
00080 namespace teb_local_planner
00081 {
00082
00084 typedef g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1> > TEBBlockSolver;
00085
00087 typedef g2o::LinearSolverCSparse<TEBBlockSolver::PoseMatrixType> TEBLinearSolver;
00088
00089
00091 typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > ViaPointContainer;
00092
00093
00105 class TebOptimalPlanner : public PlannerInterface
00106 {
00107 public:
00108
00112 TebOptimalPlanner();
00113
00122 TebOptimalPlanner(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared<PointRobotFootprint>(),
00123 TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
00124
00128 virtual ~TebOptimalPlanner();
00129
00138 void initialize(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared<PointRobotFootprint>(),
00139 TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
00140
00141
00142
00145
00163 virtual bool plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
00164
00181 virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
00182
00199 virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
00200
00201
00210 virtual bool getVelocityCommand(double& vx, double& vy, double& omega) const;
00211
00212
00239 bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards = false,
00240 double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);
00241
00243
00244
00247
00248
00255 void setVelocityStart(const geometry_msgs::Twist& vel_start);
00256
00262 void setVelocityGoal(const geometry_msgs::Twist& vel_goal);
00263
00268 void setVelocityGoalFree() {vel_goal_.first = false;}
00269
00271
00272
00275
00276
00282 void setObstVector(ObstContainer* obst_vector) {obstacles_ = obst_vector;}
00283
00288 const ObstContainer& getObstVector() const {return *obstacles_;}
00289
00291
00294
00295
00301 void setViaPoints(const ViaPointContainer* via_points) {via_points_ = via_points;}
00302
00307 const ViaPointContainer& getViaPoints() const {return *via_points_;}
00308
00310
00311
00314
00320 void setVisualization(TebVisualizationPtr visualization);
00321
00328 virtual void visualize();
00329
00331
00332
00335
00339 virtual void clearPlanner()
00340 {
00341 clearGraph();
00342 teb_.clearTimedElasticBand();
00343 }
00344
00351 static void registerG2OTypes();
00352
00358 TimedElasticBand& teb() {return teb_;};
00359
00364 const TimedElasticBand& teb() const {return teb_;};
00365
00371 boost::shared_ptr<g2o::SparseOptimizer> optimizer() {return optimizer_;};
00372
00377 boost::shared_ptr<const g2o::SparseOptimizer> optimizer() const {return optimizer_;};
00378
00384 bool isOptimized() const {return optimized_;};
00385
00407 void computeCurrentCost(double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);
00408
00417 virtual void computeCurrentCost(std::vector<double>& cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
00418 {
00419 computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
00420 cost.push_back( getCurrentCost() );
00421 }
00422
00430 double getCurrentCost() const {return cost_;}
00431
00432
00445 inline void extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const;
00446
00465 void getVelocityProfile(std::vector<geometry_msgs::Twist>& velocity_profile) const;
00466
00478 void getFullTrajectory(std::vector<TrajectoryPointMsg>& trajectory) const;
00479
00493 virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec, double inscribed_radius = 0.0,
00494 double circumscribed_radius=0.0, int look_ahead_idx=-1);
00495
00496
00510 virtual bool isHorizonReductionAppropriate(const std::vector<geometry_msgs::PoseStamped>& initial_plan) const;
00511
00513
00514 protected:
00515
00518
00531 bool buildGraph(double weight_multiplier=1.0);
00532
00545 bool optimizeGraph(int no_iterations, bool clear_after=true);
00546
00552 void clearGraph();
00553
00566 void AddTEBVertices();
00567
00574 void AddEdgesVelocity();
00575
00584 void AddEdgesAcceleration();
00585
00592 void AddEdgesTimeOptimal();
00593
00604 void AddEdgesObstacles(double weight_multiplier=1.0);
00605
00614 void AddEdgesObstaclesLegacy(double weight_multiplier=1.0);
00615
00622 void AddEdgesViaPoints();
00623
00631 void AddEdgesDynamicObstacles();
00632
00640 void AddEdgesKinematicsDiffDrive();
00641
00649 void AddEdgesKinematicsCarlike();
00650
00652
00653
00658 boost::shared_ptr<g2o::SparseOptimizer> initOptimizer();
00659
00660
00661
00662 const TebConfig* cfg_;
00663 ObstContainer* obstacles_;
00664 const ViaPointContainer* via_points_;
00665
00666 double cost_;
00667
00668
00669 TebVisualizationPtr visualization_;
00670 TimedElasticBand teb_;
00671 RobotFootprintModelPtr robot_model_;
00672 boost::shared_ptr<g2o::SparseOptimizer> optimizer_;
00673 std::pair<bool, geometry_msgs::Twist> vel_start_;
00674 std::pair<bool, geometry_msgs::Twist> vel_goal_;
00675
00676 bool initialized_;
00677 bool optimized_;
00678
00679 public:
00680 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00681 };
00682
00684 typedef boost::shared_ptr<TebOptimalPlanner> TebOptimalPlannerPtr;
00686 typedef boost::shared_ptr<const TebOptimalPlanner> TebOptimalPlannerConstPtr;
00688 typedef std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer;
00689
00690 }
00691
00692 #endif