Classes | Namespaces | Defines | Typedefs
homotopy_class_planner.h File Reference
#include <math.h>
#include <algorithm>
#include <functional>
#include <vector>
#include <iterator>
#include <boost/graph/adjacency_list.hpp>
#include <boost/graph/graph_traits.hpp>
#include <boost/graph/depth_first_search.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/random.hpp>
#include <boost/utility.hpp>
#include <visualization_msgs/Marker.h>
#include <geometry_msgs/Point.h>
#include <std_msgs/ColorRGBA.h>
#include <ros/console.h>
#include <ros/ros.h>
#include <teb_local_planner/planner_interface.h>
#include <teb_local_planner/teb_config.h>
#include <teb_local_planner/obstacles.h>
#include <teb_local_planner/optimal_planner.h>
#include <teb_local_planner/visualization.h>
#include <teb_local_planner/robot_footprint_model.h>
#include <teb_local_planner/homotopy_class_planner.hpp>
Include dependency graph for homotopy_class_planner.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  teb_local_planner::HcGraphVertex
 Vertex in the graph that is used to find homotopy classes (only stores 2D positions) More...
class  teb_local_planner::HomotopyClassPlanner
 Local planner that explores alternative homotopy classes, create a plan for each alternative and finally return the robot controls for the current best path (repeated in each sampling interval) More...

Namespaces

namespace  teb_local_planner

Defines

#define BOOST_NO_CXX11_DEFAULTED_FUNCTIONS

Typedefs

typedef boost::adjacency_list
< boost::listS, boost::vecS,
boost::directedS,
HcGraphVertex,
boost::no_property > 
teb_local_planner::HcGraph
 Abbrev. for the homotopy class search-graph type.
typedef boost::graph_traits
< HcGraph >
::adjacency_iterator 
teb_local_planner::HcGraphAdjecencyIterator
 Abbrev. for the adjacency iterator that iterates vertices that are adjecent to the specified one.
typedef boost::graph_traits
< HcGraph >::edge_iterator 
teb_local_planner::HcGraphEdgeIterator
 Abbrev. for the edges iterator of the homotopy class search-graph.
typedef boost::graph_traits
< HcGraph >::edge_descriptor 
teb_local_planner::HcGraphEdgeType
 Abbrev. for edge type descriptors in the homotopy class search-graph.
typedef boost::graph_traits
< HcGraph >::vertex_iterator 
teb_local_planner::HcGraphVertexIterator
 Abbrev. for the vertices iterator of the homotopy class search-graph.
typedef boost::graph_traits
< HcGraph >::vertex_descriptor 
teb_local_planner::HcGraphVertexType
 Abbrev. for vertex type descriptors in the homotopy class search-graph.
typedef boost::shared_ptr
< HomotopyClassPlanner > 
teb_local_planner::HomotopyClassPlannerPtr
 Abbrev. for a shared pointer of a HomotopyClassPlanner instance.

Define Documentation

Definition at line 54 of file homotopy_class_planner.h.



teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:15