Skip to content

Commit 1684cb9

Browse files
authored
fix bug in orientation filtering (#4840)
* fix bug in orientation filtering some global planners output all zeros for orientation, however the plan is in the global frame. when transforming to the local frame, the orientation is no longer zero. Instead of comparing to zero, we simply check if all the orientations in the middle of the plan are equal Signed-off-by: Michael Ferguson <[email protected]> * account for floating point error Signed-off-by: Michael Ferguson <[email protected]> --------- Signed-off-by: Michael Ferguson <[email protected]>
1 parent 78f60ee commit 1684cb9

File tree

1 file changed

+8
-4
lines changed

1 file changed

+8
-4
lines changed

nav2_graceful_controller/src/graceful_controller.cpp

+8-4
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include <memory>
1616
#include <mutex>
1717

18+
#include "angles/angles.h"
1819
#include "nav2_core/controller_exceptions.hpp"
1920
#include "nav2_util/geometry_utils.hpp"
2021
#include "nav2_graceful_controller/graceful_controller.hpp"
@@ -425,12 +426,15 @@ void GracefulController::computeDistanceAlongPath(
425426
void GracefulController::validateOrientations(
426427
std::vector<geometry_msgs::msg::PoseStamped> & path)
427428
{
428-
// This really shouldn't happen
429-
if (path.empty()) {return;}
429+
// We never change the orientation of the first & last pose
430+
// So we need at least three poses to do anything here
431+
if (path.size() < 3) {return;}
430432

431433
// Check if we actually need to add orientations
432-
for (size_t i = 1; i < path.size() - 1; ++i) {
433-
if (tf2::getYaw(path[i].pose.orientation) != 0.0) {return;}
434+
double initial_yaw = tf2::getYaw(path[1].pose.orientation);
435+
for (size_t i = 2; i < path.size() - 1; ++i) {
436+
double this_yaw = tf2::getYaw(path[i].pose.orientation);
437+
if (angles::shortest_angular_distance(this_yaw, initial_yaw) > 1e-6) {return;}
434438
}
435439

436440
// For each pose, point at the next one

0 commit comments

Comments
 (0)