Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 8 additions & 4 deletions nav2_graceful_controller/src/graceful_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <memory>
#include <mutex>

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

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

// For each pose, point at the next one
Expand Down
Loading