diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index dcb11bb795..af55acaa1f 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -81,7 +81,7 @@ void SITL_State::_sitl_setup() _update_airspeed(0); #if AP_SIM_SOLOGIMBAL_ENABLED if (enable_gimbal) { - gimbal = NEW_NOTHROW SITL::SoloGimbal(_sitl->state); + gimbal = NEW_NOTHROW SITL::SoloGimbal(); } #endif diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index cf143e28bd..54a530bc44 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -334,7 +334,7 @@ void SITL_State_Common::sim_update(void) { #if AP_SIM_SOLOGIMBAL_ENABLED if (gimbal != nullptr) { - gimbal->update(); + gimbal->update(*sitl_model); } #endif #if HAL_SIM_ADSB_ENABLED diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 30cea03245..042bb2ce7f 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -439,9 +439,11 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case 'v': vehicle_str = gopt.optarg; break; +#if AP_SIM_SOLOGIMBAL_ENABLED case CMDLINE_GIMBAL: enable_gimbal = true; break; +#endif case CMDLINE_FGVIEW: _use_fg_view = true; break;