diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index b6096f9528..884621832b 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -469,10 +469,12 @@ void AP_Mount::init() _num_instances++; #endif +#if HAL_MOUNT_STORM32SERIAL_ENABLED // check for SToRM32 mounts using serial protocol } else if (mount_type == Mount_Type_SToRM32_serial) { _backends[instance] = new AP_Mount_SToRM32_serial(*this, state[instance], instance); _num_instances++; +#endif #if HAL_MOUNT_GREMSY_ENABLED // check for Gremsy mounts diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 85ab28c3db..8c2f5d22f2 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -1,5 +1,6 @@ #include "AP_Mount_SToRM32_serial.h" -#if HAL_MOUNT_ENABLED + +#if HAL_MOUNT_STORM32SERIAL_ENABLED #include #include #include @@ -296,4 +297,4 @@ void AP_Mount_SToRM32_serial::parse_reply() { break; } } -#endif // HAL_MOUNT_ENABLED +#endif // HAL_MOUNT_STORM32SERIAL_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index 8d5b39c2f2..188f342637 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -3,14 +3,19 @@ */ #pragma once +#include "AP_Mount_Backend.h" + +#ifndef HAL_MOUNT_STORM32SERIAL_ENABLED +#define HAL_MOUNT_STORM32SERIAL_ENABLED HAL_MOUNT_ENABLED +#endif + +#if HAL_MOUNT_STORM32SERIAL_ENABLED + #include #include - #include #include #include -#include "AP_Mount_Backend.h" -#if HAL_MOUNT_ENABLED #define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second @@ -148,4 +153,4 @@ private: // keep the last _current_angle values Vector3l _current_angle; }; -#endif // HAL_MOUNT_ENABLED +#endif // HAL_MOUNT_STORM32SERIAL_ENABLED