From 3ff602335e34a455f79ba4de2d6038d46ceeaf15 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 8 Dec 2023 16:10:35 +0000 Subject: [PATCH] Rover: update for changed signature of set_target_velocity_NED() --- Rover/Rover.cpp | 2 +- Rover/Rover.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index b95de7bb49..d676be9898 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -172,7 +172,7 @@ bool Rover::set_target_location(const Location& target_loc) #if AP_SCRIPTING_ENABLED // set target velocity (for use by scripting) -bool Rover::set_target_velocity_NED(const Vector3f& vel_ned) +bool Rover::set_target_velocity_NED(const Vector3f& vel_ned, bool align_yaw_to_target) { // exit if vehicle is not in Guided mode or Auto-Guided mode if (!control_mode->in_guided_mode()) { diff --git a/Rover/Rover.h b/Rover/Rover.h index ca9ecd6079..e43a1cfeed 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -268,7 +268,7 @@ private: #endif #if AP_SCRIPTING_ENABLED - bool set_target_velocity_NED(const Vector3f& vel_ned) override; + bool set_target_velocity_NED(const Vector3f& vel_ned, bool align_yaw_to_target) override; bool set_steering_and_throttle(float steering, float throttle) override; bool get_steering_and_throttle(float& steering, float& throttle) override; // set desired turn rate (degrees/sec) and speed (m/s). Used for scripting