57 for ( boost::tie(it,end) = boost::adjacent_vertices(back,g); it!=end; ++it)
59 if ( std::find(visited.begin(), visited.end(), *it)!=visited.end() )
64 visited.push_back(*it);
68 start_orientation, goal_orientation, start_velocity);
76 for ( boost::tie(it,end) = boost::adjacent_vertices(back,g); it!=end; ++it)
78 if ( std::find(visited.begin(), visited.end(), *it)!=visited.end() || *it == goal)
82 visited.push_back(*it);
85 DepthFirst(g, visited, goal, start_orientation, goal_orientation, start_velocity);
103 ROS_DEBUG(
"HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached.");
106 ROS_INFO(
"HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors.");
112 Eigen::Vector2d normal(-diff[1],diff[0]);
114 normal = normal*dist_to_obst;
122 std::pair<HcGraphVertexType,HcGraphVertexType> nearest_obstacle;
130 Eigen::Vector2d start2obst = (*it_obst)->getCentroid() - start.
position();
131 double dist = start2obst.norm();
132 if (start2obst.dot(diff)/dist<0.1)
137 graph_[u].pos = (*it_obst)->getCentroid() + normal;
139 graph_[v].pos = (*it_obst)->getCentroid() - normal;
142 if (obstacle_heading_threshold && dist<min_dist)
145 nearest_obstacle.first = u;
146 nearest_obstacle.second = v;
164 Eigen::Vector2d distij =
graph_[*it_j].pos-
graph_[*it_i].pos;
167 if (distij.dot(diff)<=obstacle_heading_threshold)
172 if (obstacle_heading_threshold && *it_i==start_vtx && min_dist!=
DBL_MAX)
174 if (*it_j == nearest_obstacle.first || *it_j == nearest_obstacle.second)
176 Eigen::Vector2d keypoint_dist =
graph_[*it_j].pos-start.
position();
177 keypoint_dist.normalize();
180 if (start_orient_vec.dot(keypoint_dist) <= obstacle_heading_threshold)
182 ROS_DEBUG(
"createGraph() - deleted edge: limit_obstacle_heading");
192 bool collision =
false;
195 if ( (*it_obst)->checkLineIntersection(
graph_[*it_i].pos,
graph_[*it_j].pos, 0.5*dist_to_obst) )
206 boost::add_edge(*it_i,*it_j,
graph_);
212 std::vector<HcGraphVertexType> visited;
213 visited.push_back(start_vtx);
226 double start_goal_dist = diff.norm();
228 if (start_goal_dist<cfg_->goal_tolerance.xy_goal_tolerance)
230 ROS_DEBUG(
"HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached.");
233 ROS_INFO(
"HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors.");
238 Eigen::Vector2d normal(-diff.coeffRef(1),diff.coeffRef(0));
247 boost::random::uniform_real_distribution<double> distribution_y(0, area_width);
249 double phi =
atan2(diff.coeffRef(1),diff.coeffRef(0));
250 Eigen::Rotation2D<double> rot_phi(phi);
252 Eigen::Vector2d area_origin;
256 area_origin = start.
position() - 0.5*area_width*normal;
267 Eigen::Vector2d sample;
272 sample = area_origin + rot_phi*Eigen::Vector2d(distribution_x(rnd_generator_), distribution_y(rnd_generator_));
308 Eigen::Vector2d distij =
graph_[*it_j].pos-
graph_[*it_i].pos;
312 if (distij.dot(diff)<=obstacle_heading_threshold)
317 bool collision =
false;
320 if ( (*it_obst)->checkLineIntersection(
graph_[*it_i].pos,
graph_[*it_j].pos, dist_to_obst) )
330 boost::add_edge(*it_i,*it_j,
graph_);
335 std::vector<HcGraphVertexType> visited;
336 visited.push_back(start_vtx);
boost::graph_traits< HcGraph >::vertex_descriptor HcGraphVertexType
Abbrev. for vertex type descriptors in the homotopy class search-graph.
Eigen::Vector2d & position()
Access the 2D position part.
int roadmap_graph_no_samples
double roadmap_graph_area_width
< Specify the number of samples generated for creating the roadmap graph, if simple_exploration is tu...
const ObstContainer * obstacles() const
Access current obstacle container (read-only)
const TebConfig * cfg_
Config class that stores and manages all related parameters.
double xy_goal_tolerance
Allowed final euclidean distance to the goal position.
HcGraph graph_
Store the graph that is utilized to find alternative homotopy classes.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
boost::graph_traits< HcGraph >::vertex_iterator HcGraphVertexIterator
Abbrev. for the vertices iterator of the homotopy class search-graph.
void clearGraph()
Clear any existing graph of the homotopy class search.
TebOptimalPlannerPtr addAndInitNewTeb(BidirIter path_start, BidirIter path_end, Fun fun_position, double start_orientation, double goal_orientation, const geometry_msgs::Twist *start_velocity)
Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class...
HomotopyClassPlanner *const hcp_
Raw pointer to the HomotopyClassPlanner. The HomotopyClassPlanner itself is guaranteed to outlive the...
void DepthFirst(HcGraph &g, std::vector< HcGraphVertexType > &visited, const HcGraphVertexType &goal, double start_orientation, double goal_orientation, const geometry_msgs::Twist *start_velocity)
Depth First Search implementation to find all paths between the start and the specified goal vertex...
struct teb_local_planner::TebConfig::GoalTolerance goal_tolerance
Goal tolerance related parameters.
virtual void createGraph(const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist *start_velocity)
Create a graph and sample points in the global frame that can be used to explore new possible paths b...
struct teb_local_planner::TebConfig::HomotopyClasses hcp
const TebOptPlannerContainer & getTrajectoryContainer() const
Read-only access to the internal trajectory container.
boost::graph_traits< HcGraph >::adjacency_iterator HcGraphAdjecencyIterator
Abbrev. for the adjacency iterator that iterates vertices that are adjecent to the specified one...
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
double & theta()
Access the orientation part (yaw angle) of the pose.
double roadmap_graph_area_length_scale
The length of the rectangular region is determined by the distance between start and goal...
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
const Eigen::Vector2d & getVector2dFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph &graph)
boost::adjacency_list< boost::listS, boost::vecS, boost::directedS, HcGraphVertex, boost::no_property > HcGraph
Abbrev. for the homotopy class search-graph type.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
int max_number_classes
Specify the maximum number of allowed alternative homotopy classes (limits computational effort) ...
virtual void createGraph(const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist *start_velocity)
Create a graph containing points in the global frame that can be used to explore new possible paths b...