diff --git a/libraries/SITL/SIM_Gimbal.cpp b/libraries/SITL/SIM_Gimbal.cpp index addc0e11c7..789413ecc2 100644 --- a/libraries/SITL/SIM_Gimbal.cpp +++ b/libraries/SITL/SIM_Gimbal.cpp @@ -18,6 +18,7 @@ */ #include "SIM_Aircraft.h" +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include "SIM_Gimbal.h" #include @@ -30,6 +31,7 @@ Gimbal::Gimbal(const struct sitl_fdm &_fdm) : lower_joint_limits(radians(-40), radians(-135), radians(-7.5)), upper_joint_limits(radians(40), radians(45), radians(7.5)), travelLimitGain(20), + reporting_period_ms(10), seen_heartbeat(false), seen_gimbal_control(false), mav_socket(false) @@ -289,3 +291,4 @@ void Gimbal::send_report(void) delta_angle.zero(); } } +#endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_Gimbal.h b/libraries/SITL/SIM_Gimbal.h index e10803c876..a5e4a34ccb 100644 --- a/libraries/SITL/SIM_Gimbal.h +++ b/libraries/SITL/SIM_Gimbal.h @@ -21,6 +21,7 @@ #define _SIM_GIMBAL_H #include "SIM_Aircraft.h" +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include class Gimbal @@ -67,7 +68,7 @@ private: // MAVLink at approx 100Hz // reporting period in ms - static const float reporting_period_ms = 10; + const float reporting_period_ms; // integral of gyro vector over last time interval. In radians Vector3f delta_angle; @@ -104,5 +105,6 @@ private: void send_report(void); }; +#endif // CONFIG_HAL_BOARD #endif // _SIM_GIMBAL_H