From 7701be8209e6acef6e5d4be5990e2f7e646da7a0 Mon Sep 17 00:00:00 2001 From: haarshitgarg <59084710+haarshitgarg@users.noreply.github.com> Date: Wed, 1 May 2024 13:43:49 -0600 Subject: [PATCH] Rover: enabled sending waypoints from a companion computer to ardupilot for copter and rover Signed-off-by: Ryan Friedman --- Rover/AP_ExternalControl_Rover.cpp | 6 ++++++ Rover/AP_ExternalControl_Rover.h | 9 ++++++++- Rover/Rover.cpp | 6 ++++-- Rover/Rover.h | 5 ++++- 4 files changed, 22 insertions(+), 4 deletions(-) diff --git a/Rover/AP_ExternalControl_Rover.cpp b/Rover/AP_ExternalControl_Rover.cpp index 1c08f92a9b5fd..d7511f6f0f832 100644 --- a/Rover/AP_ExternalControl_Rover.cpp +++ b/Rover/AP_ExternalControl_Rover.cpp @@ -29,6 +29,12 @@ bool AP_ExternalControl_Rover::set_linear_velocity_and_yaw_rate(const Vector3f & return true; } +bool AP_ExternalControl_Rover::set_global_position(const Location& loc) +{ + // set_target_location only checks if the rover is in guided mode or not + return rover.set_target_location(loc); +} + bool AP_ExternalControl_Rover::ready_for_external_control() { return rover.control_mode->in_guided_mode() && rover.arming.is_armed(); diff --git a/Rover/AP_ExternalControl_Rover.h b/Rover/AP_ExternalControl_Rover.h index 434972833e45d..e7350ebbe2c62 100644 --- a/Rover/AP_ExternalControl_Rover.h +++ b/Rover/AP_ExternalControl_Rover.h @@ -7,7 +7,8 @@ #if AP_EXTERNAL_CONTROL_ENABLED -class AP_ExternalControl_Rover : public AP_ExternalControl { +class AP_ExternalControl_Rover : public AP_ExternalControl +{ public: /* Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw. @@ -15,6 +16,12 @@ class AP_ExternalControl_Rover : public AP_ExternalControl { Yaw is in earth frame, NED [rad/s]. */ bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads)override WARN_IF_UNUSED; + + /* + Sets the global position for loiter point + */ + bool set_global_position(const Location& loc) override WARN_IF_UNUSED; + private: /* Return true if Rover is ready to handle external control data. diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index f1a47b452545d..1278977b59a91 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -157,8 +157,8 @@ Rover::Rover(void) : { } -#if AP_SCRIPTING_ENABLED -// set target location (for use by scripting) +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +// set target location (for use by external control and scripting) bool Rover::set_target_location(const Location& target_loc) { // exit if vehicle is not in Guided mode or Auto-Guided mode @@ -168,7 +168,9 @@ bool Rover::set_target_location(const Location& target_loc) return mode_guided.set_desired_location(target_loc); } +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED // set target velocity (for use by scripting) bool Rover::set_target_velocity_NED(const Vector3f& vel_ned) { diff --git a/Rover/Rover.h b/Rover/Rover.h index 6b2493d4fc7a5..0db95d23b3997 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -269,8 +269,11 @@ class Rover : public AP_Vehicle { cruise_learn_t cruise_learn; // Rover.cpp -#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED bool set_target_location(const Location& target_loc) override; +#endif + +#if AP_SCRIPTING_ENABLED bool set_target_velocity_NED(const Vector3f& vel_ned) override; bool set_steering_and_throttle(float steering, float throttle) override; bool get_steering_and_throttle(float& steering, float& throttle) override;