Skip to content

Commit 9e62442

Browse files
LinusTxtonomySteveMacenski
authored andcommitted
Update Smac Planner for rounding to closest bin rather than flooring (ros-navigation#4636) (ros-navigation#4760)
Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
1 parent e02a144 commit 9e62442

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
@@ -250,8 +250,8 @@ MotionPoses HybridMotionTable::getProjections(const NodeHybrid * node)
250250

251251
unsigned int HybridMotionTable::getClosestAngularBin(const double & theta)
252252
{
253-
return static_cast<unsigned int>(floor(theta / static_cast<double>(bin_size))) %
254-
num_angle_quantization;
253+
auto bin = static_cast<unsigned int>(round(static_cast<float>(theta) / bin_size));
254+
return bin < num_angle_quantization ? bin : 0u;
255255
}
256256

257257
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
@@ -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;

nav2_smac_planner/test/test_nodehybrid.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -323,7 +323,7 @@ TEST(NodeHybridTest, basic_get_closest_angular_bin_test)
323323
{
324324
motion_table.bin_size = M_PI;
325325
motion_table.num_angle_quantization = 2;
326-
double test_theta = M_PI;
326+
double test_theta = M_PI / 2.0 - 0.000001;
327327
unsigned int expected_angular_bin = 0;
328328
unsigned int calculated_angular_bin = motion_table.getClosestAngularBin(test_theta);
329329
EXPECT_EQ(expected_angular_bin, calculated_angular_bin);
@@ -341,8 +341,8 @@ TEST(NodeHybridTest, basic_get_closest_angular_bin_test)
341341
{
342342
motion_table.bin_size = 0.0872664675;
343343
motion_table.num_angle_quantization = 72;
344-
double test_theta = 6.28318526567925;
345-
unsigned int expected_angular_bin = 71;
344+
double test_theta = 6.28317530718; // 0.0001 less than 2 pi
345+
unsigned int expected_angular_bin = 0; // should be closer to wrap around
346346
unsigned int calculated_angular_bin = motion_table.getClosestAngularBin(test_theta);
347347
EXPECT_EQ(expected_angular_bin, calculated_angular_bin);
348348
}

0 commit comments

Comments
 (0)