From 2f7e07069fbf4fa0080340f6b8c2b51ea1ab0abd Mon Sep 17 00:00:00 2001 From: Josh Henderson Date: Mon, 4 Oct 2021 06:17:04 -0400 Subject: [PATCH] Replay: move AP_Airspeed to AP_Vehicle --- Tools/Replay/Replay.cpp | 2 ++ Tools/Replay/Replay.h | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 5c23b3eddd..c42085e5b7 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -58,9 +58,11 @@ const AP_Param::Info ReplayVehicle::var_info[] = { // @Path: ../libraries/AP_AHRS/AP_AHRS.cpp GOBJECT(ahrs, "AHRS_", AP_AHRS), +#if AP_AIRSPEED_ENABLED // @Group: ARSPD_ // @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp GOBJECT(airspeed, "ARSP_", AP_Airspeed), +#endif // @Group: EK2_ // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 6fef0ef4af..2e72bb5ba5 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -46,7 +46,7 @@ public: virtual uint8_t get_mode() const override { return 0; } AP_Vehicle::FixedWing aparm; - AP_Airspeed airspeed; + AP_Int32 unused; // logging is magic for Replay; this is unused struct LogStructure log_structure[256] = { };