@@ -297,33 +297,31 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
297297 std::to_string (start.pose .position .y ) + " ) was outside bounds" );
298298 }
299299
300- double orientation_bin = tf2::getYaw (start.pose .orientation ) / _angle_bin_size;
300+ double orientation_bin = std::round ( tf2::getYaw (start.pose .orientation ) / _angle_bin_size) ;
301301 while (orientation_bin < 0.0 ) {
302302 orientation_bin += static_cast <float >(_angle_quantizations);
303303 }
304304 // This is needed to handle precision issues
305305 if (orientation_bin >= static_cast <float >(_angle_quantizations)) {
306306 orientation_bin -= static_cast <float >(_angle_quantizations);
307307 }
308- unsigned int orientation_bin_id = static_cast <unsigned int >(floor (orientation_bin));
309- _a_star->setStart (mx, my, orientation_bin_id);
308+ _a_star->setStart (mx, my, static_cast <unsigned int >(orientation_bin));
310309
311310 // Set goal point, in A* bin search coordinates
312311 if (!costmap->worldToMap (goal.pose .position .x , goal.pose .position .y , mx, my)) {
313312 throw nav2_core::GoalOutsideMapBounds (
314313 " Goal Coordinates of(" + std::to_string (goal.pose .position .x ) + " , " +
315314 std::to_string (goal.pose .position .y ) + " ) was outside bounds" );
316315 }
317- orientation_bin = tf2::getYaw (goal.pose .orientation ) / _angle_bin_size;
316+ orientation_bin = std::round ( tf2::getYaw (goal.pose .orientation ) / _angle_bin_size) ;
318317 while (orientation_bin < 0.0 ) {
319318 orientation_bin += static_cast <float >(_angle_quantizations);
320319 }
321320 // This is needed to handle precision issues
322321 if (orientation_bin >= static_cast <float >(_angle_quantizations)) {
323322 orientation_bin -= static_cast <float >(_angle_quantizations);
324323 }
325- orientation_bin_id = static_cast <unsigned int >(floor (orientation_bin));
326- _a_star->setGoal (mx, my, orientation_bin_id);
324+ _a_star->setGoal (mx, my, static_cast <unsigned int >(orientation_bin));
327325
328326 // Setup message
329327 nav_msgs::msg::Path plan;
0 commit comments