@@ -367,33 +367,31 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
367367 std::to_string (start.pose .position .y ) + " ) was outside bounds" );
368368 }
369369
370- double orientation_bin = tf2::getYaw (start.pose .orientation ) / _angle_bin_size;
370+ double orientation_bin = std::round ( tf2::getYaw (start.pose .orientation ) / _angle_bin_size) ;
371371 while (orientation_bin < 0.0 ) {
372372 orientation_bin += static_cast <float >(_angle_quantizations);
373373 }
374374 // This is needed to handle precision issues
375375 if (orientation_bin >= static_cast <float >(_angle_quantizations)) {
376376 orientation_bin -= static_cast <float >(_angle_quantizations);
377377 }
378- unsigned int orientation_bin_id = static_cast <unsigned int >(floor (orientation_bin));
379- _a_star->setStart (mx, my, orientation_bin_id);
378+ _a_star->setStart (mx, my, static_cast <unsigned int >(orientation_bin));
380379
381380 // Set goal point, in A* bin search coordinates
382381 if (!costmap->worldToMapContinuous (goal.pose .position .x , goal.pose .position .y , mx, my)) {
383382 throw nav2_core::GoalOutsideMapBounds (
384383 " Goal Coordinates of(" + std::to_string (goal.pose .position .x ) + " , " +
385384 std::to_string (goal.pose .position .y ) + " ) was outside bounds" );
386385 }
387- orientation_bin = tf2::getYaw (goal.pose .orientation ) / _angle_bin_size;
386+ orientation_bin = std::round ( tf2::getYaw (goal.pose .orientation ) / _angle_bin_size) ;
388387 while (orientation_bin < 0.0 ) {
389388 orientation_bin += static_cast <float >(_angle_quantizations);
390389 }
391390 // This is needed to handle precision issues
392391 if (orientation_bin >= static_cast <float >(_angle_quantizations)) {
393392 orientation_bin -= static_cast <float >(_angle_quantizations);
394393 }
395- orientation_bin_id = static_cast <unsigned int >(floor (orientation_bin));
396- _a_star->setGoal (mx, my, orientation_bin_id);
394+ _a_star->setGoal (mx, my, static_cast <unsigned int >(orientation_bin));
397395
398396 // Setup message
399397 nav_msgs::msg::Path plan;
0 commit comments