graph_search.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Authors: Christoph Rösmann, Franz Albers
37  *********************************************************************/
38 
41 
42 namespace teb_local_planner
43 {
44 
45 void GraphSearchInterface::DepthFirst(HcGraph& g, std::vector<HcGraphVertexType>& visited, const HcGraphVertexType& goal, double start_orientation,
46  double goal_orientation, const geometry_msgs::Twist* start_velocity)
47 {
48  // see http://www.technical-recipes.com/2011/a-recursive-algorithm-to-find-all-paths-between-two-given-nodes/ for details on finding all simple paths
49 
50  if ((int)hcp_->getTrajectoryContainer().size() >= cfg_->hcp.max_number_classes)
51  return; // We do not need to search for further possible alternative homotopy classes.
52 
53  HcGraphVertexType back = visited.back();
54 
57  for ( boost::tie(it,end) = boost::adjacent_vertices(back,g); it!=end; ++it)
58  {
59  if ( std::find(visited.begin(), visited.end(), *it)!=visited.end() )
60  continue; // already visited
61 
62  if ( *it == goal ) // goal reached
63  {
64  visited.push_back(*it);
65 
66  // Add new TEB, if this path belongs to a new homotopy class
67  hcp_->addAndInitNewTeb(visited.begin(), visited.end(), boost::bind(getVector2dFromHcGraph, _1, boost::cref(graph_)),
68  start_orientation, goal_orientation, start_velocity);
69 
70  visited.pop_back();
71  break;
72  }
73  }
74 
76  for ( boost::tie(it,end) = boost::adjacent_vertices(back,g); it!=end; ++it)
77  {
78  if ( std::find(visited.begin(), visited.end(), *it)!=visited.end() || *it == goal)
79  continue; // already visited || goal reached
80 
81 
82  visited.push_back(*it);
83 
84  // recursion step
85  DepthFirst(g, visited, goal, start_orientation, goal_orientation, start_velocity);
86 
87  visited.pop_back();
88  }
89 }
90 
91 
92 
93 void lrKeyPointGraph::createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity)
94 {
95  // Clear existing graph and paths
96  clearGraph();
97 
98  // Direction-vector between start and goal and normal-vector:
99  Eigen::Vector2d diff = goal.position()-start.position();
100 
101  if (diff.norm()<cfg_->goal_tolerance.xy_goal_tolerance)
102  {
103  ROS_DEBUG("HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached.");
104  if (hcp_->getTrajectoryContainer().empty())
105  {
106  ROS_INFO("HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors.");
107  hcp_->addAndInitNewTeb(start, goal, start_velocity);
108  }
109  return;
110  }
111 
112  Eigen::Vector2d normal(-diff[1],diff[0]); // normal-vector
113  normal.normalize();
114  normal = normal*dist_to_obst; // scale with obstacle_distance;
115 
116  // Insert Vertices
117  HcGraphVertexType start_vtx = boost::add_vertex(graph_); // start vertex
118  graph_[start_vtx].pos = start.position();
119  diff.normalize();
120 
121  // store nearest obstacle keypoints -> only used if limit_obstacle_heading is enabled
122  std::pair<HcGraphVertexType,HcGraphVertexType> nearest_obstacle; // both vertices are stored
123  double min_dist = DBL_MAX;
124 
125  if (hcp_->obstacles()!=NULL)
126  {
127  for (ObstContainer::const_iterator it_obst = hcp_->obstacles()->begin(); it_obst != hcp_->obstacles()->end(); ++it_obst)
128  {
129  // check if obstacle is placed in front of start point
130  Eigen::Vector2d start2obst = (*it_obst)->getCentroid() - start.position();
131  double dist = start2obst.norm();
132  if (start2obst.dot(diff)/dist<0.1)
133  continue;
134 
135  // Add Keypoints
136  HcGraphVertexType u = boost::add_vertex(graph_);
137  graph_[u].pos = (*it_obst)->getCentroid() + normal;
138  HcGraphVertexType v = boost::add_vertex(graph_);
139  graph_[v].pos = (*it_obst)->getCentroid() - normal;
140 
141  // store nearest obstacle
142  if (obstacle_heading_threshold && dist<min_dist)
143  {
144  min_dist = dist;
145  nearest_obstacle.first = u;
146  nearest_obstacle.second = v;
147  }
148  }
149  }
150 
151  HcGraphVertexType goal_vtx = boost::add_vertex(graph_); // goal vertex
152  graph_[goal_vtx].pos = goal.position();
153 
154  // Insert Edges
155  HcGraphVertexIterator it_i, end_i, it_j, end_j;
156  for (boost::tie(it_i,end_i) = boost::vertices(graph_); it_i!=end_i-1; ++it_i) // ignore goal in this loop
157  {
158  for (boost::tie(it_j,end_j) = boost::vertices(graph_); it_j!=end_j; ++it_j) // check all forward connections
159  {
160  if (it_i==it_j)
161  continue;
162  // TODO: make use of knowing in which order obstacles are inserted and that for each obstacle 2 vertices are added,
163  // therefore we must only check one of them.
164  Eigen::Vector2d distij = graph_[*it_j].pos-graph_[*it_i].pos;
165  distij.normalize();
166  // Check if the direction is backwards:
167  if (distij.dot(diff)<=obstacle_heading_threshold)
168  continue;
169 
170 
171  // Check start angle to nearest obstacle
172  if (obstacle_heading_threshold && *it_i==start_vtx && min_dist!=DBL_MAX)
173  {
174  if (*it_j == nearest_obstacle.first || *it_j == nearest_obstacle.second)
175  {
176  Eigen::Vector2d keypoint_dist = graph_[*it_j].pos-start.position();
177  keypoint_dist.normalize();
178  Eigen::Vector2d start_orient_vec( cos(start.theta()), sin(start.theta()) ); // already normalized
179  // check angle
180  if (start_orient_vec.dot(keypoint_dist) <= obstacle_heading_threshold)
181  {
182  ROS_DEBUG("createGraph() - deleted edge: limit_obstacle_heading");
183  continue;
184  }
185  }
186  }
187 
188  // Collision Check
189 
190  if (hcp_->obstacles()!=NULL)
191  {
192  bool collision = false;
193  for (ObstContainer::const_iterator it_obst = hcp_->obstacles()->begin(); it_obst != hcp_->obstacles()->end(); ++it_obst)
194  {
195  if ( (*it_obst)->checkLineIntersection(graph_[*it_i].pos,graph_[*it_j].pos, 0.5*dist_to_obst) )
196  {
197  collision = true;
198  break;
199  }
200  }
201  if (collision)
202  continue;
203  }
204 
205  // Create Edge
206  boost::add_edge(*it_i,*it_j,graph_);
207  }
208  }
209 
210 
211  // Find all paths between start and goal!
212  std::vector<HcGraphVertexType> visited;
213  visited.push_back(start_vtx);
214  DepthFirst(graph_,visited,goal_vtx, start.theta(), goal.theta(), start_velocity);
215 }
216 
217 
218 
219 void ProbRoadmapGraph::createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity)
220 {
221  // Clear existing graph and paths
222  clearGraph();
223 
224  // Direction-vector between start and goal and normal-vector:
225  Eigen::Vector2d diff = goal.position()-start.position();
226  double start_goal_dist = diff.norm();
227 
228  if (start_goal_dist<cfg_->goal_tolerance.xy_goal_tolerance)
229  {
230  ROS_DEBUG("HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached.");
231  if (hcp_->getTrajectoryContainer().empty())
232  {
233  ROS_INFO("HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors.");
234  hcp_->addAndInitNewTeb(start, goal, start_velocity);
235  }
236  return;
237  }
238  Eigen::Vector2d normal(-diff.coeffRef(1),diff.coeffRef(0)); // normal-vector
239  normal.normalize();
240 
241  // Now sample vertices between start, goal and a specified width between both sides
242  // Let's start with a square area between start and goal (maybe change it later to something like a circle or whatever)
243 
244  double area_width = cfg_->hcp.roadmap_graph_area_width;
245 
246  boost::random::uniform_real_distribution<double> distribution_x(0, start_goal_dist * cfg_->hcp.roadmap_graph_area_length_scale);
247  boost::random::uniform_real_distribution<double> distribution_y(0, area_width);
248 
249  double phi = atan2(diff.coeffRef(1),diff.coeffRef(0)); // rotate area by this angle
250  Eigen::Rotation2D<double> rot_phi(phi);
251 
252  Eigen::Vector2d area_origin;
254  area_origin = start.position() + 0.5*(1.0-cfg_->hcp.roadmap_graph_area_length_scale)*start_goal_dist*diff.normalized() - 0.5*area_width*normal; // bottom left corner of the origin
255  else
256  area_origin = start.position() - 0.5*area_width*normal; // bottom left corner of the origin
257 
258  // Insert Vertices
259  HcGraphVertexType start_vtx = boost::add_vertex(graph_); // start vertex
260  graph_[start_vtx].pos = start.position();
261  diff.normalize(); // normalize in place
262 
263 
264  // Start sampling
265  for (int i=0; i < cfg_->hcp.roadmap_graph_no_samples; ++i)
266  {
267  Eigen::Vector2d sample;
268 // bool coll_free;
269 // do // sample as long as a collision free sample is found
270 // {
271  // Sample coordinates
272  sample = area_origin + rot_phi*Eigen::Vector2d(distribution_x(rnd_generator_), distribution_y(rnd_generator_));
273 
274  // Test for collision
275  // we do not care for collision checking here to improve efficiency, since we perform resampling repeatedly.
276  // occupied vertices are ignored in the edge insertion state since they always violate the edge-obstacle collision check.
277 // coll_free = true;
278 // for (ObstContainer::const_iterator it_obst = obstacles_->begin(); it_obst != obstacles_->end(); ++it_obst)
279 // {
280 // if ( (*it_obst)->checkCollision(sample, dist_to_obst)) // TODO really keep dist_to_obst here?
281 // {
282 // coll_free = false;
283 // break;
284 // }
285 // }
286 //
287 // } while (!coll_free && ros::ok());
288 
289  // Add new vertex
290  HcGraphVertexType v = boost::add_vertex(graph_);
291  graph_[v].pos = sample;
292  }
293 
294  // Now add goal vertex
295  HcGraphVertexType goal_vtx = boost::add_vertex(graph_); // goal vertex
296  graph_[goal_vtx].pos = goal.position();
297 
298 
299  // Insert Edges
300  HcGraphVertexIterator it_i, end_i, it_j, end_j;
301  for (boost::tie(it_i,end_i) = boost::vertices(graph_); it_i!=boost::prior(end_i); ++it_i) // ignore goal in this loop
302  {
303  for (boost::tie(it_j,end_j) = boost::vertices(graph_); it_j!=end_j; ++it_j) // check all forward connections
304  {
305  if (it_i==it_j) // same vertex found
306  continue;
307 
308  Eigen::Vector2d distij = graph_[*it_j].pos-graph_[*it_i].pos;
309  distij.normalize(); // normalize in place
310 
311  // Check if the direction is backwards:
312  if (distij.dot(diff)<=obstacle_heading_threshold)
313  continue; // diff is already normalized
314 
315 
316  // Collision Check
317  bool collision = false;
318  for (ObstContainer::const_iterator it_obst = hcp_->obstacles()->begin(); it_obst != hcp_->obstacles()->end(); ++it_obst)
319  {
320  if ( (*it_obst)->checkLineIntersection(graph_[*it_i].pos,graph_[*it_j].pos, dist_to_obst) )
321  {
322  collision = true;
323  break;
324  }
325  }
326  if (collision)
327  continue;
328 
329  // Create Edge
330  boost::add_edge(*it_i,*it_j,graph_);
331  }
332  }
333 
335  std::vector<HcGraphVertexType> visited;
336  visited.push_back(start_vtx);
337  DepthFirst(graph_,visited,goal_vtx, start.theta(), goal.theta(), start_velocity);
338 }
339 
340 } // end namespace
boost::graph_traits< HcGraph >::vertex_descriptor HcGraphVertexType
Abbrev. for vertex type descriptors in the homotopy class search-graph.
Definition: graph_search.h:82
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:145
double roadmap_graph_area_width
< Specify the number of samples generated for creating the roadmap graph, if simple_exploration is tu...
Definition: teb_config.h:177
const ObstContainer * obstacles() const
Access current obstacle container (read-only)
const TebConfig * cfg_
Config class that stores and manages all related parameters.
Definition: graph_search.h:144
double xy_goal_tolerance
Allowed final euclidean distance to the goal position.
Definition: teb_config.h:107
HcGraph graph_
Store the graph that is utilized to find alternative homotopy classes.
Definition: graph_search.h:120
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.
Definition: graph_search.h:86
void clearGraph()
Clear any existing graph of the homotopy class search.
Definition: graph_search.h:116
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...
Definition: graph_search.h:145
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...
#define DBL_MAX
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
#define ROS_INFO(...)
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...
Definition: graph_search.h:90
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Definition: pose_se2.h:57
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: pose_se2.h:182
double roadmap_graph_area_length_scale
The length of the rectangular region is determined by the distance between start and goal...
Definition: teb_config.h:178
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)
Definition: graph_search.h:99
boost::adjacency_list< boost::listS, boost::vecS, boost::directedS, HcGraphVertex, boost::no_property > HcGraph
Abbrev. for the homotopy class search-graph type.
Definition: graph_search.h:80
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) ...
Definition: teb_config.h:168
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...
#define ROS_DEBUG(...)


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 5 2019 19:25:10