From b0bd78818eba7a2e967363a978b236aa646b144e Mon Sep 17 00:00:00 2001 From: Sergi Hernandez Juan <shernand@iri.upc.edu> Date: Thu, 11 Feb 2021 23:38:51 +0100 Subject: [PATCH] Added a check that the index of the best path is valid before getting the trajectory. --- src/opendrive_planner.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/opendrive_planner.cpp b/src/opendrive_planner.cpp index 0120635..36ed297 100644 --- a/src/opendrive_planner.cpp +++ b/src/opendrive_planner.cpp @@ -271,6 +271,8 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c std::cout << std::endl; } best_path_index=this->roadmap.get_best_path(best_cost,best_path); + if(best_path_index==-1) + return false; std::cout << "best path index: " << best_path_index << std::endl; for(unsigned int i=0;i<best_path.size();i++) std::cout << best_path[i] << ","; -- GitLab