#include <boost/graph/adjacency_list.hpp>
#include <boost/graph/graph_traits.hpp>
#include <boost/graph/depth_first_search.hpp>
#include <boost/utility.hpp>
#include <boost/random.hpp>
#include <Eigen/Core>
#include <geometry_msgs/Twist.h>
#include <teb_local_planner/equivalence_relations.h>
#include <teb_local_planner/pose_se2.h>
#include <teb_local_planner/teb_config.h>
Go to the source code of this file.
Classes | |
class | teb_local_planner::GraphSearchInterface |
Base class for graph based path planning / homotopy class sampling. More... | |
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::lrKeyPointGraph |
class | teb_local_planner::ProbRoadmapGraph |
Namespaces | |
teb_local_planner | |
Macros | |
#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. More... | |
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. More... | |
typedef boost::graph_traits< HcGraph >::edge_iterator | teb_local_planner::HcGraphEdgeIterator |
Abbrev. for the edges iterator of the homotopy class search-graph. More... | |
typedef boost::graph_traits< HcGraph >::edge_descriptor | teb_local_planner::HcGraphEdgeType |
Abbrev. for edge type descriptors in the homotopy class search-graph. More... | |
typedef boost::graph_traits< HcGraph >::vertex_iterator | teb_local_planner::HcGraphVertexIterator |
Abbrev. for the vertices iterator of the homotopy class search-graph. More... | |
typedef boost::graph_traits< HcGraph >::vertex_descriptor | teb_local_planner::HcGraphVertexType |
Abbrev. for vertex type descriptors in the homotopy class search-graph. More... | |
Functions | |
std::complex< long double > | teb_local_planner::getCplxFromHcGraph (HcGraphVertexType vert_descriptor, const HcGraph &graph) |
Inline function used for initializing the TEB in combination with HCP graph vertex descriptors. More... | |
const Eigen::Vector2d & | teb_local_planner::getVector2dFromHcGraph (HcGraphVertexType vert_descriptor, const HcGraph &graph) |
#define BOOST_NO_CXX11_DEFAULTED_FUNCTIONS |
Definition at line 48 of file graph_search.h.