40 #include <nav_msgs/Path.h>
41 #include <sbpl_lattice_planner/SBPLLatticePlannerStats.h>
56 return p1.x == p2.x && p1.y == p2.y && p1.z == p2.z;
64 LatticeSCQ(EnvironmentNAVXYTHETALAT* env, std::vector<nav2dcell_t>
const & changedcellsV)
65 : env_(env), changedcellsV_(changedcellsV) {
70 if(predsOfChangedCells_.empty() && !changedcellsV_.empty())
71 env_->GetPredsofChangedEdges(&changedcellsV_, &predsOfChangedCells_);
72 return &predsOfChangedCells_;
77 if(succsOfChangedCells_.empty() && !changedcellsV_.empty())
78 env_->GetSuccsofChangedEdges(&changedcellsV_, &succsOfChangedCells_);
79 return &succsOfChangedCells_;
82 EnvironmentNAVXYTHETALAT *
env_;
88 SBPLLatticePlanner::SBPLLatticePlanner()
89 : initialized_(false), costmap_ros_(NULL){
93 : initialized_(false), costmap_ros_(NULL){
102 ROS_INFO(
"Name is %s", name.c_str());
112 double nominalvel_mpersecs, timetoturn45degsinplace_secs;
113 private_nh.
param(
"nominalvel_mpersecs", nominalvel_mpersecs, 0.4);
114 private_nh.
param(
"timetoturn45degsinplace_secs", timetoturn45degsinplace_secs, 0.6);
117 private_nh.
param(
"lethal_obstacle",lethal_obstacle,20);
134 ROS_DEBUG(
"Using a 3D costmap for theta lattice\n");
135 env_ =
new EnvironmentNAVXYTHETALAT();
138 ROS_ERROR(
"XYThetaLattice is currently the only supported environment!\n");
152 ROS_WARN(
"SBPL performance will suffer.");
153 ROS_WARN(
"Please decrease the costmap's cost_scaling_factor.");
156 ROS_ERROR(
"Failed to set cost_inscribed_thresh parameter");
160 ROS_ERROR(
"Failed to set cost_possibly_circumscribed_thresh parameter");
164 vector<sbpl_2Dpt_t> perimeterptsV;
166 for (
size_t ii(0); ii <
footprint_.size(); ++ii) {
170 perimeterptsV.push_back(pt);
182 timetoturn45degsinplace_secs, obst_cost_thresh,
187 catch(SBPL_Exception *e){
188 ROS_ERROR(
"SBPL encountered a fatal exception: %s", e->what());
192 ROS_ERROR(
"SBPL initialization failed!");
208 ROS_ERROR(
"ARAPlanner and ADPlanner are currently the only supported planners!\n");
212 ROS_INFO(
"[sbpl_lattice_planner] Initialized successfully");
239 const geometry_msgs::PoseStamped& start,
240 const geometry_msgs::PoseStamped& goal){
242 sbpl_lattice_planner::SBPLLatticePlannerStats stats;
244 stats.plan_to_first_solution =
false;
245 stats.final_number_of_expands =
planner_->get_n_expands();
248 stats.time_to_first_solution =
planner_->get_initial_eps_planning_time();
249 stats.actual_time =
planner_->get_final_eps_planning_time();
250 stats.number_of_expands_initial_solution =
planner_->get_n_expands_init_solution();
251 stats.final_epsilon =
planner_->get_final_epsilon();
253 stats.solution_cost = solution_cost;
254 stats.path_size = solution_size;
261 unsigned char result = 0;
273 if (!inflation_layer)
continue;
281 const geometry_msgs::PoseStamped& goal,
282 std::vector<geometry_msgs::PoseStamped>& plan){
284 ROS_ERROR(
"Global planner is not initialized");
288 bool do_init =
false;
291 ROS_INFO(
"Costmap dimensions have changed from (%d x %d) to (%d x %d), reinitializing sbpl_lattice_planner.",
297 ROS_INFO(
"Robot footprint has changed, reinitializing sbpl_lattice_planner.");
301 ROS_INFO(
"Cost at circumscribed radius has changed, reinitializing sbpl_lattice_planner.");
316 ROS_INFO(
"[sbpl_lattice_planner] getting start point (%g,%g) goal point (%g,%g)",
317 start.pose.position.x,
start.pose.position.y,goal.pose.position.x, goal.pose.position.y);
318 double theta_start = 2 * atan2(
start.pose.orientation.z,
start.pose.orientation.w);
319 double theta_goal = 2 * atan2(goal.pose.orientation.z, goal.pose.orientation.w);
323 if(ret < 0 || planner_->set_start(ret) == 0){
324 ROS_ERROR(
"ERROR: failed to set start state\n");
328 catch(SBPL_Exception *e){
329 ROS_ERROR(
"SBPL encountered a fatal exception while setting the start state");
335 if(ret < 0 || planner_->set_goal(ret) == 0){
336 ROS_ERROR(
"ERROR: failed to set goal state\n");
340 catch(SBPL_Exception *e){
341 ROS_ERROR(
"SBPL encountered a fatal exception while setting the goal state");
348 vector<nav2dcell_t> changedcellsV;
353 unsigned char oldCost =
env_->GetMapCost(ix,iy);
356 if(oldCost == newCost)
continue;
373 nav2dcell_t nav2dcell;
376 changedcellsV.push_back(nav2dcell);
381 if(!changedcellsV.empty()){
388 planner_->force_planning_from_scratch();
390 catch(SBPL_Exception *e){
391 ROS_ERROR(
"SBPL failed to update the costmap");
400 ROS_DEBUG(
"[sbpl_lattice_planner] run planner");
401 vector<int> solution_stateIDs;
413 catch(SBPL_Exception *e){
414 ROS_ERROR(
"SBPL encountered a fatal exception while planning");
418 ROS_DEBUG(
"size of solution=%d", (
int)solution_stateIDs.size());
420 vector<EnvNAVXYTHETALAT3Dpt_t> sbpl_path;
422 env_->ConvertStateIDPathintoXYThetaPath(&solution_stateIDs, &sbpl_path);
424 catch(SBPL_Exception *e){
425 ROS_ERROR(
"SBPL encountered a fatal exception while reconstructing the path");
429 if( sbpl_path.size() == 0 ) {
430 EnvNAVXYTHETALAT3Dpt_t
s(
434 sbpl_path.push_back(
s);
437 ROS_DEBUG(
"Plan has %d points.\n", (
int)sbpl_path.size());
442 visualization_msgs::Marker sbpl_plan_footprint;
448 nav_msgs::Path gui_path;
449 gui_path.poses.resize(sbpl_path.size());
451 gui_path.header.stamp = plan_time;
452 for(
unsigned int i=0; i<sbpl_path.size(); i++){
453 geometry_msgs::PoseStamped pose;
454 pose.header.stamp = plan_time;
459 pose.pose.position.z =
start.pose.position.z;
462 temp.
setRPY(0,0,sbpl_path[i].theta);
463 pose.pose.orientation.x = temp.getX();
464 pose.pose.orientation.y = temp.getY();
465 pose.pose.orientation.z = temp.getZ();
466 pose.pose.orientation.w = temp.
getW();
468 plan.push_back(pose);
470 gui_path.poses[i] = plan[i];
479 const std::string& path_frame_id, visualization_msgs::Marker& ma)
481 ma.header.frame_id = path_frame_id;
483 ma.ns =
"sbpl_robot_footprint";
485 ma.type = visualization_msgs::Marker::LINE_LIST;
486 ma.action = visualization_msgs::Marker::ADD;
492 ma.pose.orientation.w = 1.0;
496 std::vector<geometry_msgs::Point> transformed_rfp;
497 geometry_msgs::Pose robot_pose;
502 robot_pose.position.z = 0.0;
504 quat.
setRPY(0.0, 0.0, sbpl_path[i].theta);
508 for (
auto & point : transformed_rfp)
509 ma.points.push_back(point);
514 const std::vector<geometry_msgs::Point>& footprint,
515 std::vector<geometry_msgs::Point>& out_footprint)
517 out_footprint.resize(2 * footprint.size());
518 double yaw =
tf::getYaw(robot_pose.orientation);
519 for (
unsigned int i = 0; i < footprint.size(); i++)
521 out_footprint[2 * i].x = robot_pose.position.x + cos(yaw) * footprint[i].x - sin(yaw) * footprint[i].y;
522 out_footprint[2 * i].y = robot_pose.position.y + sin(yaw) * footprint[i].x + cos(yaw) * footprint[i].y;
525 out_footprint.back().x = out_footprint[i].x;
526 out_footprint.back().y = out_footprint[i].y;
530 out_footprint[2 * i - 1].x = out_footprint[2 * i].x;
531 out_footprint[2 * i - 1].y = out_footprint[2 * i].y;