Skip to content

Commit a63090f

Browse files
Update Smac Planner for rounding to closest bin rather than flooring (ros-navigation#4636)
1 parent c2e4aab commit a63090f

File tree

3 files changed

+9
-11
lines changed

3 files changed

+9
-11
lines changed

nav2_smac_planner/src/node_hybrid.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -330,8 +330,8 @@ MotionPoses HybridMotionTable::getProjections(const NodeHybrid * node)
330330

331331
unsigned int HybridMotionTable::getClosestAngularBin(const double & theta)
332332
{
333-
return static_cast<unsigned int>(floor(theta / static_cast<double>(bin_size))) %
334-
num_angle_quantization;
333+
auto bin = static_cast<unsigned int>(round(static_cast<float>(theta) / bin_size));
334+
return bin < num_angle_quantization ? bin : 0u;
335335
}
336336

337337
float HybridMotionTable::getAngleFromBin(const unsigned int & bin_idx)

nav2_smac_planner/src/smac_planner_hybrid.cpp

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -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;

nav2_smac_planner/test/test_nodehybrid.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -396,7 +396,7 @@ TEST(NodeHybridTest, basic_get_closest_angular_bin_test)
396396
{
397397
motion_table.bin_size = M_PI;
398398
motion_table.num_angle_quantization = 2;
399-
double test_theta = M_PI;
399+
double test_theta = M_PI / 2.0 - 0.000001;
400400
unsigned int expected_angular_bin = 0;
401401
unsigned int calculated_angular_bin = motion_table.getClosestAngularBin(test_theta);
402402
EXPECT_EQ(expected_angular_bin, calculated_angular_bin);
@@ -414,8 +414,8 @@ TEST(NodeHybridTest, basic_get_closest_angular_bin_test)
414414
{
415415
motion_table.bin_size = 0.0872664675;
416416
motion_table.num_angle_quantization = 72;
417-
double test_theta = 6.28318526567925;
418-
unsigned int expected_angular_bin = 71;
417+
double test_theta = 6.28317530718; // 0.0001 less than 2 pi
418+
unsigned int expected_angular_bin = 0; // should be closer to wrap around
419419
unsigned int calculated_angular_bin = motion_table.getClosestAngularBin(test_theta);
420420
EXPECT_EQ(expected_angular_bin, calculated_angular_bin);
421421
}

0 commit comments

Comments
 (0)