From caee9f271a6cd7db4cef2da0559bcde534275331 Mon Sep 17 00:00:00 2001 From: tzarjakob Date: Wed, 22 Mar 2023 09:45:41 +0100 Subject: [PATCH] Rover: configuration of Precision Landing for custom build server --- Rover/GCS_Mavlink.cpp | 2 +- Rover/Parameters.cpp | 2 +- Rover/Rover.cpp | 2 +- Rover/Rover.h | 7 ++++--- Rover/config.h | 8 +------- Rover/precision_landing.cpp | 2 +- Rover/system.cpp | 2 +- 7 files changed, 10 insertions(+), 15 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index acfa8699b9..92d1742651 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -1063,7 +1063,7 @@ void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg) */ void GCS_MAVLINK_Rover::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED rover.precland.handle_msg(packet, timestamp_ms); #endif } diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 1de13e3f6b..89738d9cae 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -297,7 +297,7 @@ const AP_Param::Info Rover::var_info[] = { GOBJECT(camera, "CAM", AP_Camera), #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // @Group: PLND_ // @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp GOBJECT(precland, "PLND_", AC_PrecLand), diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index bb6f56120a..f264315234 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -98,7 +98,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { #if AP_GRIPPER_ENABLED SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69), #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED SCHED_TASK(update_precland, 400, 50, 70), #endif #if AP_RPM_ENABLED diff --git a/Rover/Rover.h b/Rover/Rover.h index b06a257033..f11bae3d60 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -42,6 +42,7 @@ #include #include #include +#include // Configuration #include "defines.h" @@ -61,10 +62,10 @@ #include "GCS_Mavlink.h" #include "GCS_Rover.h" #include "AP_Rally.h" -#include "RC_Channel.h" // RC Channel Library -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED #include #endif +#include "RC_Channel.h" // RC Channel Library #include "mode.h" @@ -145,7 +146,7 @@ private: #if OSD_ENABLED || OSD_PARAM_ENABLED AP_OSD osd; #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED AC_PrecLand precland; #endif // GCS handling diff --git a/Rover/config.h b/Rover/config.h index 6983f9d122..77b2981c5f 100644 --- a/Rover/config.h +++ b/Rover/config.h @@ -38,12 +38,6 @@ #define AP_RALLY ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// Precision Landing with companion computer or IRLock sensor -#ifndef PRECISION_LANDING - # define PRECISION_LANDING ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // NAVL1 // @@ -70,7 +64,7 @@ ////////////////////////////////////////////////////////////////////////////// // Dock mode - allows vehicle to dock to a docking target #ifndef MODE_DOCK_ENABLED -# define MODE_DOCK_ENABLED PRECISION_LANDING +# define MODE_DOCK_ENABLED AC_PRECLAND_ENABLED #endif diff --git a/Rover/precision_landing.cpp b/Rover/precision_landing.cpp index 12b33174eb..c62b499b6a 100644 --- a/Rover/precision_landing.cpp +++ b/Rover/precision_landing.cpp @@ -4,7 +4,7 @@ #include "Rover.h" -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED void Rover::init_precland() { diff --git a/Rover/system.cpp b/Rover/system.cpp index c7a17b10d5..78e4107254 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -117,7 +117,7 @@ void Rover::init_ardupilot() camera.init(); #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precision landing init_precland(); #endif