Classes | Namespaces | Typedefs
optimal_planner.h File Reference
#include <math.h>
#include <teb_local_planner/teb_config.h>
#include <teb_local_planner/misc.h>
#include <teb_local_planner/timed_elastic_band.h>
#include <teb_local_planner/planner_interface.h>
#include <teb_local_planner/visualization.h>
#include <teb_local_planner/robot_footprint_model.h>
#include "g2o/core/sparse_optimizer.h"
#include "g2o/core/block_solver.h"
#include "g2o/core/factory.h"
#include "g2o/core/optimization_algorithm_gauss_newton.h"
#include "g2o/core/optimization_algorithm_levenberg.h"
#include "g2o/solvers/csparse/linear_solver_csparse.h"
#include "g2o/solvers/cholmod/linear_solver_cholmod.h"
#include <teb_local_planner/g2o_types/edge_velocity.h>
#include <teb_local_planner/g2o_types/edge_acceleration.h>
#include <teb_local_planner/g2o_types/edge_kinematics.h>
#include <teb_local_planner/g2o_types/edge_time_optimal.h>
#include <teb_local_planner/g2o_types/edge_shortest_path.h>
#include <teb_local_planner/g2o_types/edge_obstacle.h>
#include <teb_local_planner/g2o_types/edge_dynamic_obstacle.h>
#include <teb_local_planner/g2o_types/edge_via_point.h>
#include <teb_local_planner/g2o_types/edge_prefer_rotdir.h>
#include <nav_msgs/Path.h>
#include <geometry_msgs/PoseStamped.h>
#include <tf/transform_datatypes.h>
#include <teb_local_planner/TrajectoryMsg.h>
#include <nav_msgs/Odometry.h>
#include <limits.h>
Include dependency graph for optimal_planner.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  teb_local_planner::TebOptimalPlanner
 This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework. More...
 

Namespaces

 teb_local_planner
 

Typedefs

typedef g2o::BlockSolver< g2o::BlockSolverTraits<-1,-1 > > teb_local_planner::TEBBlockSolver
 Typedef for the block solver utilized for optimization. More...
 
typedef g2o::LinearSolverCSparse< TEBBlockSolver::PoseMatrixType > teb_local_planner::TEBLinearSolver
 Typedef for the linear solver utilized for optimization. More...
 
typedef boost::shared_ptr< const TebOptimalPlanner > teb_local_planner::TebOptimalPlannerConstPtr
 Abbrev. for shared const TebOptimalPlanner pointers. More...
 
typedef boost::shared_ptr< TebOptimalPlanner > teb_local_planner::TebOptimalPlannerPtr
 Abbrev. for shared instances of the TebOptimalPlanner. More...
 
typedef std::vector< TebOptimalPlannerPtr > teb_local_planner::TebOptPlannerContainer
 Abbrev. for containers storing multiple teb optimal planners. More...
 
typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > teb_local_planner::ViaPointContainer
 Typedef for a container storing via-points. More...
 


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 3 2020 04:03:08