mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 16:08:28 -04:00
AP_HAL_SITL: adjust for renaming of Gimbal to SoloGimbal
This commit is contained in:
parent
1ce6aa7e38
commit
9b3809c89f
libraries/AP_HAL_SITL
@ -79,9 +79,11 @@ void SITL_State::_sitl_setup()
|
|||||||
if (_sitl != nullptr) {
|
if (_sitl != nullptr) {
|
||||||
// setup some initial values
|
// setup some initial values
|
||||||
_update_airspeed(0);
|
_update_airspeed(0);
|
||||||
|
#if AP_SIM_SOLOGIMBAL_ENABLED
|
||||||
if (enable_gimbal) {
|
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_buzzer(&_sitl->buzzer_sim);
|
||||||
sitl_model->set_sprayer(&_sitl->sprayer_sim);
|
sitl_model->set_sprayer(&_sitl->sprayer_sim);
|
||||||
|
@ -332,7 +332,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||||||
*/
|
*/
|
||||||
void SITL_State_Common::sim_update(void)
|
void SITL_State_Common::sim_update(void)
|
||||||
{
|
{
|
||||||
#if HAL_SIM_GIMBAL_ENABLED
|
#if AP_SIM_SOLOGIMBAL_ENABLED
|
||||||
if (gimbal != nullptr) {
|
if (gimbal != nullptr) {
|
||||||
gimbal->update();
|
gimbal->update();
|
||||||
}
|
}
|
||||||
|
@ -9,7 +9,7 @@
|
|||||||
#define SITL_SERVO_PORT 20722
|
#define SITL_SERVO_PORT 20722
|
||||||
|
|
||||||
#include <AP_HAL/utility/Socket_native.h>
|
#include <AP_HAL/utility/Socket_native.h>
|
||||||
#include <SITL/SIM_Gimbal.h>
|
#include <SITL/SIM_SoloGimbal.h>
|
||||||
#include <SITL/SIM_ADSB.h>
|
#include <SITL/SIM_ADSB.h>
|
||||||
#include <SITL/SIM_ADSB_Sagetech_MXS.h>
|
#include <SITL/SIM_ADSB_Sagetech_MXS.h>
|
||||||
#include <SITL/SIM_EFI_Hirth.h>
|
#include <SITL/SIM_EFI_Hirth.h>
|
||||||
@ -104,11 +104,11 @@ public:
|
|||||||
bool new_rc_input;
|
bool new_rc_input;
|
||||||
uint16_t pwm_output[SITL_NUM_CHANNELS];
|
uint16_t pwm_output[SITL_NUM_CHANNELS];
|
||||||
bool output_ready = false;
|
bool output_ready = false;
|
||||||
|
|
||||||
#if HAL_SIM_GIMBAL_ENABLED
|
#if AP_SIM_SOLOGIMBAL_ENABLED
|
||||||
// simulated gimbal
|
// simulated gimbal
|
||||||
bool enable_gimbal;
|
bool enable_gimbal;
|
||||||
SITL::Gimbal *gimbal;
|
SITL::SoloGimbal *gimbal;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAL_SIM_ADSB_ENABLED
|
#if HAL_SIM_ADSB_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user