From b5461d4de582d1321d8de7a0bcfb93bd89985d36 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:28 +1100 Subject: [PATCH 01/18] AC_PrecLand: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AC_PrecLand/AC_PrecLand.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index c97742a855c2d..01b664154796c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -14,6 +14,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; From 7c25d680d45782863cbc1e92a9bf1ff925be7f41 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:28 +1100 Subject: [PATCH 02/18] AP_AHRS: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_AHRS/AP_AHRS.cpp | 8 ++++++++ libraries/AP_AHRS/AP_AHRS.h | 4 +--- libraries/AP_AHRS/AP_AHRS_Backend.cpp | 19 +++++++++++++++++++ libraries/AP_AHRS/AP_AHRS_Backend.h | 17 ++--------------- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 1 + libraries/AP_AHRS/AP_AHRS_External.cpp | 1 + 6 files changed, 32 insertions(+), 18 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index e8fa5cd623a61..9c7216f32c7fa 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -278,6 +278,14 @@ void AP_AHRS::init() #endif // AP_CUSTOMROTATIONS_ENABLED } +const Vector3f &AP_AHRS::get_accel(void) const { +#if AP_INERTIALSENSOR_ENABLED + return AP::ins().get_accel(_get_primary_accel_index()); +#else + return Vector3f(); +#endif +} + // updates matrices responsible for rotating vectors from vehicle body // frame to autopilot body frame from _trim variables void AP_AHRS::update_trim_rotation_matrices() diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 04ce489dad7e3..8d4720abad155 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -619,9 +619,7 @@ class AP_AHRS { Vector3f get_vibration(void) const; // return primary accels - const Vector3f &get_accel(void) const { - return AP::ins().get_accel(_get_primary_accel_index()); - } + const Vector3f &get_accel(void) const; // return primary accel bias. This should be subtracted from // get_accel() vector to get best current body frame accel diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.cpp b/libraries/AP_AHRS/AP_AHRS_Backend.cpp index aac74a5a23e14..4314c24813608 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Backend.cpp @@ -19,6 +19,7 @@ #include #include +#include #include #include #include @@ -31,6 +32,24 @@ void AP_AHRS_Backend::init() { } +// get the index of the current primary accelerometer sensor +uint8_t AP_AHRS_Backend::get_primary_accel_index(void) const { +#if AP_INERTIALSENSOR_ENABLED + return AP::ins().get_first_usable_accel(); +#else + return 0; +#endif +} + +// get the index of the current primary gyro sensor +uint8_t AP_AHRS_Backend::get_primary_gyro_index(void) const { +#if AP_INERTIALSENSOR_ENABLED + return AP::ins().get_first_usable_gyro(); +#else + return 0; +#endif +} + // return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet) Vector3f AP_AHRS::get_gyro_latest(void) const { diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index 99ad8f2dc82c9..76bd0a6f6d7f1 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -23,7 +23,6 @@ #include #include #include -#include #include #include @@ -76,22 +75,10 @@ class AP_AHRS_Backend virtual int8_t get_primary_core_index() const { return -1; } // get the index of the current primary accelerometer sensor - virtual uint8_t get_primary_accel_index(void) const { -#if AP_INERTIALSENSOR_ENABLED - return AP::ins().get_first_usable_accel(); -#else - return 0; -#endif - } + virtual uint8_t get_primary_accel_index(void) const; // get the index of the current primary gyro sensor - virtual uint8_t get_primary_gyro_index(void) const { -#if AP_INERTIALSENSOR_ENABLED - return AP::ins().get_first_usable_gyro(); -#else - return 0; -#endif - } + virtual uint8_t get_primary_gyro_index(void) const; // Methods virtual void update() = 0; diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index a9179502d3324..5256e2bcbb8a5 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -31,6 +31,7 @@ #include #include #include +#include #include #include diff --git a/libraries/AP_AHRS/AP_AHRS_External.cpp b/libraries/AP_AHRS/AP_AHRS_External.cpp index 435bda69b471a..aa2ad0dbb3a6e 100644 --- a/libraries/AP_AHRS/AP_AHRS_External.cpp +++ b/libraries/AP_AHRS/AP_AHRS_External.cpp @@ -4,6 +4,7 @@ #include #include +#include // true if the AHRS has completed initialisation bool AP_AHRS_External::initialised(void) const From 815c9f9fcf764824e5796356f3facf41f281485f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:28 +1100 Subject: [PATCH 03/18] AP_GyroFFT: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_GyroFFT/AP_GyroFFT.cpp | 6 ++++++ libraries/AP_GyroFFT/AP_GyroFFT.h | 7 ++----- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.cpp b/libraries/AP_GyroFFT/AP_GyroFFT.cpp index 54c47dc6caa1f..b237cf4755597 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.cpp +++ b/libraries/AP_GyroFFT/AP_GyroFFT.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) #include #endif @@ -428,6 +429,11 @@ void AP_GyroFFT::update() } } +uint16_t AP_GyroFFT::get_available_samples(uint8_t axis) +{ + return _sample_mode == 0 ?_ins->get_raw_gyro_window(axis).available() : _downsampled_gyro_data[axis].available(); +} + // analyse gyro data using FFT, returns number of samples still held // called from FFT thread uint16_t AP_GyroFFT::run_cycle() diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.h b/libraries/AP_GyroFFT/AP_GyroFFT.h index 115448227b308..05cd9e8960a16 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.h +++ b/libraries/AP_GyroFFT/AP_GyroFFT.h @@ -24,7 +24,6 @@ #include #include #include -#include #include #include @@ -221,9 +220,7 @@ class AP_GyroFFT // whether analysis can be run again or not bool start_analysis(); // return samples available in the gyro window - uint16_t get_available_samples(uint8_t axis) { - return _sample_mode == 0 ?_ins->get_raw_gyro_window(axis).available() : _downsampled_gyro_data[axis].available(); - } + uint16_t get_available_samples(uint8_t axis); void update_parameters(bool force); // semaphore for access to shared FFT data HAL_Semaphore _sem; @@ -358,7 +355,7 @@ class AP_GyroFFT AP_Int8 _num_frames; // mask of IMUs to record gyro frames after the filter bank AP_Int32 _options; - AP_InertialSensor* _ins; + class AP_InertialSensor* _ins; #if DEBUG_FFT uint32_t _last_output_ms; EngineState _debug_state; From 0c9ff583eddefc3e8f0eff7158c0c0c981714751 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:28 +1100 Subject: [PATCH 04/18] AP_InertialSensor: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_InertialSensor/FastRateBuffer.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/FastRateBuffer.h b/libraries/AP_InertialSensor/FastRateBuffer.h index 77ce3e267915c..4f6ab2084e425 100644 --- a/libraries/AP_InertialSensor/FastRateBuffer.h +++ b/libraries/AP_InertialSensor/FastRateBuffer.h @@ -14,7 +14,7 @@ */ #pragma once -#include "AP_InertialSensor.h" +#include "AP_InertialSensor_rate_config.h" #if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED From 54543f7deb78d412ca5e08d54db718eef2821f21 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:28 +1100 Subject: [PATCH 05/18] APM_Control: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/APM_Control/AP_YawController.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index 0da792112bef9..fd1e2878d52f0 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -22,6 +22,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; From ae7d65edad715193ffdd9fab8c3f55b5dcb73d8a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:28 +1100 Subject: [PATCH 06/18] AP_Mount: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_Mount/AP_Mount_SoloGimbal.cpp | 1 + libraries/AP_Mount/SoloGimbal.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 251c859693b2d..97116722550e7 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -5,6 +5,7 @@ #include "AP_Mount_SoloGimbal.h" #include "SoloGimbal.h" +#include #include #include #include diff --git a/libraries/AP_Mount/SoloGimbal.cpp b/libraries/AP_Mount/SoloGimbal.cpp index 6e270de10251a..c6356cdb830f5 100644 --- a/libraries/AP_Mount/SoloGimbal.cpp +++ b/libraries/AP_Mount/SoloGimbal.cpp @@ -8,6 +8,7 @@ #include #include +#include #include extern const AP_HAL::HAL& hal; From e99a59f9ea6e8a2ea0c025cd504b80c59743d072 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:28 +1100 Subject: [PATCH 07/18] AP_NavEKF3: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_NavEKF3/AP_NavEKF3_core.h | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index ee4d17a6f5c51..3e4cfdef80ba0 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -31,7 +31,6 @@ #include #include #include -#include #include #include "AP_NavEKF/EKFGSF_yaw.h" From fbfc83b226398733606d85c18460ae2dfaabb15a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:28 +1100 Subject: [PATCH 08/18] AP_NMEA_Output: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_NMEA_Output/AP_NMEA_Output.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp index 836445abeecb6..99dece37a6422 100644 --- a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp +++ b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp @@ -31,6 +31,7 @@ #include #include #include +#include #if AP_AHRS_ENABLED #include From 28d8dc312e4250d4eddc4c9be40ab29e38e17a88 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:29 +1100 Subject: [PATCH 09/18] AP_Soaring: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_Soaring/Variometer.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index 67e33fba03d8b..e9269ba2efcf4 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -5,6 +5,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. #include "Variometer.h" #include +#include #include Variometer::Variometer(const AP_FixedWing &parms, const PolarParams &polarParams) : From 979fb2549e4f13fa20de056025e9addcca769b6a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:29 +1100 Subject: [PATCH 10/18] AP_TECS: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_TECS/AP_TECS.cpp | 1 + libraries/AP_TECS/AP_TECS.h | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index b0cbe34087e29..589b6b441cc93 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -4,6 +4,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index 484177ed920d9..9645d4d00a0b2 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -22,6 +22,7 @@ #include #include #include +#include class AP_Landing; class AP_TECS { From 775166dfd93df26e0bd82b151909aaef4f9e532a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:29 +1100 Subject: [PATCH 11/18] AP_TempCalibration: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/AP_TempCalibration/AP_TempCalibration.cpp | 2 ++ libraries/AP_TempCalibration/AP_TempCalibration.h | 3 +-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_TempCalibration/AP_TempCalibration.cpp b/libraries/AP_TempCalibration/AP_TempCalibration.cpp index f9b6c07a5b033..1ad5f6ba43acd 100644 --- a/libraries/AP_TempCalibration/AP_TempCalibration.cpp +++ b/libraries/AP_TempCalibration/AP_TempCalibration.cpp @@ -23,6 +23,8 @@ #include "AP_TempCalibration.h" #include #include +#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_TempCalibration/AP_TempCalibration.h b/libraries/AP_TempCalibration/AP_TempCalibration.h index 0b8eecc68fc44..2cd8563367a1d 100644 --- a/libraries/AP_TempCalibration/AP_TempCalibration.h +++ b/libraries/AP_TempCalibration/AP_TempCalibration.h @@ -22,9 +22,8 @@ #if AP_TEMPCALIBRATION_ENABLED -#include +#include #include -#include class AP_TempCalibration { From 551d57ca9298ee5278f28011e880c32d24786607 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:29 +1100 Subject: [PATCH 12/18] GCS_MAVLink: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/GCS_MAVLink/GCS.cpp | 1 + libraries/GCS_MAVLink/GCS_Common.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index c4a11f666d55d..8dbfeb12de8cf 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include "MissionItemProtocol_Waypoints.h" #include "MissionItemProtocol_Rally.h" diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 91dfd299c3142..6231b4f714bd7 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include #include From c53c01aab22814cf8c06d4565a8bf067ba957a34 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:29 +1100 Subject: [PATCH 13/18] RC_Channel: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- libraries/RC_Channel/RC_Channel.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index bae3499173bec..5fe43762b19a2 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -40,6 +40,7 @@ extern const AP_HAL::HAL& hal; #include #include #include +#include #include #include #include From aa40fd761114e61a1f985d8d3573c152444f572a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:29 +1100 Subject: [PATCH 14/18] ArduCopter: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- ArduCopter/Copter.h | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index a94edddef298b..e2dd146d35892 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -37,7 +37,6 @@ #include // ArduPilot Mega Flash Memory Library #include // ArduPilot Mega Vector/Matrix math Library #include // interface and maths for accelerometer calibration -#include // ArduPilot Mega Inertial Sensor (accel & gyro) Library #include // AHRS (Attitude Heading Reference System) interface library for ArduPilot #include // Mission command library #include // Mission command change detection library From 0c780a8aaf574e879ece065a47a4b634a084f044 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:29 +1100 Subject: [PATCH 15/18] ArduPlane: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- ArduPlane/Plane.h | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index df180b6f745a0..d00b7d3d7ee7c 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -35,7 +35,6 @@ #include #include #include // ArduPilot Mega Vector/Matrix math Library -#include // Inertial Sensor Library #include // interface and maths for accelerometer calibration #include // ArduPilot Mega DCM Library #include From 21bec4b64fea1ccea3dffd4f7c615694de41ac7d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:30 +1100 Subject: [PATCH 16/18] ArduSub: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- ArduSub/Sub.h | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 9c6e621bc45f1..2a6f02da8f2e1 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -41,7 +41,6 @@ #include // ArduPilot Mega Flash Memory Library #include #include // ArduPilot Mega Magnetometer Library -#include // ArduPilot Mega Inertial Sensor (accel & gyro) Library #include #include // Mission command library #include // Attitude control library From dbd5b1d4c38056708f6c8b86ab3a2b055158b720 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 12:52:30 +1100 Subject: [PATCH 17/18] Blimp: avoid including AP_InertialSensor.h in headers increases amount of work compiler needs to do for no good reason --- Blimp/Blimp.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index aa4d2e449d3cc..2b859d3c14773 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -36,8 +36,6 @@ // Application dependencies #include // ArduPilot Mega Flash Memory Library #include // ArduPilot Mega Vector/Matrix math Library -// #include // interface and maths for accelerometer calibration -// #include // ArduPilot Mega Inertial Sensor (accel & gyro) Library #include #include // Filter library #include // needed for AHRS build From aea6ba497d14a594c888668318ebdf30624cb5d7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Dec 2024 13:35:12 +1100 Subject: [PATCH 18/18] AP_Module: avoid including AP_InertialSensor.h in headers --- libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp index cecee126ac774..7e626f934799c 100644 --- a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp +++ b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp @@ -9,6 +9,7 @@ #include #include #include +#include const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPEND