diff --git a/nav2_bt_navigator/src/navigators/navigate_to_pose.cpp b/nav2_bt_navigator/src/navigators/navigate_to_pose.cpp index 7a521a210d..1ddb0f82ae 100644 --- a/nav2_bt_navigator/src/navigators/navigate_to_pose.cpp +++ b/nav2_bt_navigator/src/navigators/navigate_to_pose.cpp @@ -179,7 +179,7 @@ NavigateToPoseNavigator::onLoop() } // Add orientation difference to distance - if (current_angular_speed > 0.01) { + if (current_angular_speed > 0.01 && current_path.poses.size() > 0) { tf2::Quaternion q( current_pose.pose.orientation.x, current_pose.pose.orientation.y,