optimal_planner.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016,
00006  *  TU Dortmund - Institute of Control Theory and Systems Engineering.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the institute nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * Author: Christoph Rösmann
00037  *********************************************************************/
00038 
00039 #ifndef OPTIMAL_PLANNER_H_
00040 #define OPTIMAL_PLANNER_H_
00041 
00042 #include <math.h>
00043 
00044 
00045 // teb stuff
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 // g2o lib stuff
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 // g2o custom edges and vertices for the TEB planner
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 // messages
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 //typedef g2o::LinearSolverCholmod<TEBBlockSolver::PoseMatrixType> TEBLinearSolver;
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   // external objects (store weak pointers)
00662   const TebConfig* cfg_; 
00663   ObstContainer* obstacles_; 
00664   const ViaPointContainer* via_points_; 
00665   
00666   double cost_; 
00667   
00668   // internal objects (memory management owned)
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 } // namespace teb_local_planner
00691 
00692 #endif /* OPTIMAL_PLANNER_H_ */


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sat Jun 8 2019 20:21:34