diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 2d49bb606b..dcb11bb795 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -79,9 +79,11 @@ void SITL_State::_sitl_setup() if (_sitl != nullptr) { // setup some initial values _update_airspeed(0); +#if AP_SIM_SOLOGIMBAL_ENABLED if (enable_gimbal) { - gimbal = NEW_NOTHROW SITL::Gimbal(_sitl->state); + gimbal = NEW_NOTHROW SITL::SoloGimbal(_sitl->state); } +#endif sitl_model->set_buzzer(&_sitl->buzzer_sim); sitl_model->set_sprayer(&_sitl->sprayer_sim); diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index 1a45ed97d9..cf143e28bd 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -332,7 +332,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const */ void SITL_State_Common::sim_update(void) { -#if HAL_SIM_GIMBAL_ENABLED +#if AP_SIM_SOLOGIMBAL_ENABLED if (gimbal != nullptr) { gimbal->update(); } diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index 7bb4c04348..95ef129c1c 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -9,7 +9,7 @@ #define SITL_SERVO_PORT 20722 #include -#include +#include #include #include #include @@ -104,11 +104,11 @@ public: bool new_rc_input; uint16_t pwm_output[SITL_NUM_CHANNELS]; bool output_ready = false; - -#if HAL_SIM_GIMBAL_ENABLED + +#if AP_SIM_SOLOGIMBAL_ENABLED // simulated gimbal bool enable_gimbal; - SITL::Gimbal *gimbal; + SITL::SoloGimbal *gimbal; #endif #if HAL_SIM_ADSB_ENABLED