Skip to content

Commit

Permalink
throw exceptions if out of bounds (#4224)
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski authored Mar 28, 2024
1 parent 9b13893 commit 1ff1303
Showing 1 changed file with 6 additions and 2 deletions.
8 changes: 6 additions & 2 deletions nav2_smac_planner/src/smac_planner_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,9 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(

// Set starting point, in A* bin search coordinates
unsigned int mx, my;
costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my);
if (!costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my)) {
throw std::runtime_error("Start pose is out of costmap!");
}
double orientation_bin = tf2::getYaw(start.pose.orientation) / _angle_bin_size;
while (orientation_bin < 0.0) {
orientation_bin += static_cast<float>(_angle_quantizations);
Expand All @@ -300,7 +302,9 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
_a_star->setStart(mx, my, orientation_bin_id);

// Set goal point, in A* bin search coordinates
costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my);
if (!costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my)) {
throw std::runtime_error("Goal pose is out of costmap!");
}
orientation_bin = tf2::getYaw(goal.pose.orientation) / _angle_bin_size;
while (orientation_bin < 0.0) {
orientation_bin += static_cast<float>(_angle_quantizations);
Expand Down

0 comments on commit 1ff1303

Please sign in to comment.