Skip to content

Commit 973a8ab

Browse files
mikefergusonSteveMacenski
authored andcommitted
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 83652b3 commit 973a8ab

File tree

1 file changed

+11
-4
lines changed

1 file changed

+11
-4
lines changed

nav2_graceful_controller/src/graceful_controller.cpp

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include <memory>
16+
#include <mutex>
17+
18+
#include "angles/angles.h"
1519
#include "nav2_core/controller_exceptions.hpp"
1620
#include "nav2_util/geometry_utils.hpp"
1721
#include "nav2_graceful_controller/graceful_controller.hpp"
@@ -422,12 +426,15 @@ void GracefulController::computeDistanceAlongPath(
422426
void GracefulController::validateOrientations(
423427
std::vector<geometry_msgs::msg::PoseStamped> & path)
424428
{
425-
// This really shouldn't happen
426-
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;}
427432

428433
// Check if we actually need to add orientations
429-
for (size_t i = 1; i < path.size() - 1; ++i) {
430-
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;}
431438
}
432439

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

0 commit comments

Comments
 (0)