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, free_goal_vel);
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, free_goal_vel);
100 Eigen::Vector2d diff = goal.position()-
start.position();
104 ROS_DEBUG(
"HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached.");
107 ROS_INFO(
"HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors.");
113 Eigen::Vector2d normal(-diff[1],diff[0]);
115 normal = normal*dist_to_obst;
123 std::pair<HcGraphVertexType,HcGraphVertexType> nearest_obstacle;
131 Eigen::Vector2d start2obst = (*it_obst)->getCentroid() -
start.position();
132 double dist = start2obst.norm();
133 if (start2obst.dot(diff)/dist<0.1)
138 graph_[u].pos = (*it_obst)->getCentroid() + normal;
140 graph_[v].pos = (*it_obst)->getCentroid() - normal;
143 if (obstacle_heading_threshold && dist<min_dist)
146 nearest_obstacle.first = u;
147 nearest_obstacle.second = v;
153 graph_[goal_vtx].pos = goal.position();
165 Eigen::Vector2d distij =
graph_[*it_j].pos-
graph_[*it_i].pos;
168 if (distij.dot(diff)<=obstacle_heading_threshold)
173 if (obstacle_heading_threshold && *it_i==start_vtx && min_dist!=DBL_MAX)
175 if (*it_j == nearest_obstacle.first || *it_j == nearest_obstacle.second)
177 Eigen::Vector2d keypoint_dist =
graph_[*it_j].pos-
start.position();
178 keypoint_dist.normalize();
179 Eigen::Vector2d start_orient_vec( cos(
start.theta()), sin(
start.theta()) );
181 if (start_orient_vec.dot(keypoint_dist) <= obstacle_heading_threshold)
183 ROS_DEBUG(
"createGraph() - deleted edge: limit_obstacle_heading");
193 bool collision =
false;
196 if ( (*it_obst)->checkLineIntersection(
graph_[*it_i].pos,
graph_[*it_j].pos, 0.5*dist_to_obst) )
207 boost::add_edge(*it_i,*it_j,
graph_);
213 std::vector<HcGraphVertexType> visited;
214 visited.push_back(start_vtx);
227 Eigen::Vector2d diff = goal.position()-
start.position();
228 double start_goal_dist = diff.norm();
230 if (start_goal_dist<cfg_->goal_tolerance.xy_goal_tolerance)
232 ROS_DEBUG(
"HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached.");
235 ROS_INFO(
"HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors.");
240 Eigen::Vector2d normal(-diff.coeffRef(1),diff.coeffRef(0));
249 boost::random::uniform_real_distribution<double> distribution_y(0, area_width);
251 double phi = atan2(diff.coeffRef(1),diff.coeffRef(0));
252 Eigen::Rotation2D<double> rot_phi(phi);
254 Eigen::Vector2d area_origin;
258 area_origin =
start.position() - 0.5*area_width*normal;
269 Eigen::Vector2d sample;
298 graph_[goal_vtx].pos = goal.position();
310 Eigen::Vector2d distij =
graph_[*it_j].pos-
graph_[*it_i].pos;
314 if (distij.dot(diff)<=obstacle_heading_threshold)
319 bool collision =
false;
322 if ( (*it_obst)->checkLineIntersection(
graph_[*it_i].pos,
graph_[*it_j].pos, dist_to_obst) )
332 boost::add_edge(*it_i,*it_j,
graph_);
337 std::vector<HcGraphVertexType> visited;
338 visited.push_back(start_vtx);