mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 21:18:29 -04:00
AP_HAL_SITL: add Volz simulator
This commit is contained in:
parent
b43410a021
commit
a6c3fb8336
@ -392,9 +392,24 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_SIM_VOLZ_ENABLED
|
||||||
|
// update simulation input based on data received via "serial" to
|
||||||
|
// Volz servos:
|
||||||
|
if (_sitl->volz_sim.enabled()) {
|
||||||
|
_sitl->volz_sim.update_sitl_input_pwm(input);
|
||||||
|
for (uint8_t i=0; i<ARRAY_SIZE(input.servos); i++) {
|
||||||
|
if (input.servos[i] != 0 && input.servos[i] < 1000) {
|
||||||
|
AP_HAL::panic("Bad input servo value (%u)", input.servos[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
const float engine_mul = _sitl->engine_mul.get();
|
const float engine_mul = _sitl->engine_mul.get();
|
||||||
const uint32_t engine_fail = _sitl->engine_fail.get();
|
const uint32_t engine_fail = _sitl->engine_fail.get();
|
||||||
|
|
||||||
|
float throttle = 0.0f;
|
||||||
|
|
||||||
// apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter
|
// apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE(input.servos); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE(input.servos); i++) {
|
||||||
if (engine_fail & (1<<i)) {
|
if (engine_fail & (1<<i)) {
|
||||||
|
@ -204,6 +204,11 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
|||||||
sitl_model->set_ie24(&_sitl->ie24_sim);
|
sitl_model->set_ie24(&_sitl->ie24_sim);
|
||||||
return &_sitl->ie24_sim;
|
return &_sitl->ie24_sim;
|
||||||
#endif // HAL_BUILD_AP_PERIPH
|
#endif // HAL_BUILD_AP_PERIPH
|
||||||
|
#if AP_SIM_VOLZ_ENABLED
|
||||||
|
} else if (streq(name, "volz")) {
|
||||||
|
sitl_model->set_volz(&_sitl->volz_sim);
|
||||||
|
return &_sitl->volz_sim;
|
||||||
|
#endif // AP_SIM_VOLZ_ENABLED
|
||||||
} else if (streq(name, "megasquirt")) {
|
} else if (streq(name, "megasquirt")) {
|
||||||
if (efi_ms != nullptr) {
|
if (efi_ms != nullptr) {
|
||||||
AP_HAL::panic("Only one megasquirt at a time");
|
AP_HAL::panic("Only one megasquirt at a time");
|
||||||
|
Loading…
Reference in New Issue
Block a user