AP_HAL_SITL: add simulated FETtec ESC

do not overwrite FETTecESC telemetry data w/SITL ESC data
This commit is contained in:
Peter Barker 2021-06-29 00:24:15 +02:00 committed by Randy Mackay
parent 8cffcde7bd
commit 443912ed9f
3 changed files with 34 additions and 0 deletions

View File

@ -85,6 +85,14 @@ void RCOutput::push(void)
memcpy(_sitlState->pwm_output, _pending, SITL_NUM_CHANNELS * sizeof(uint16_t));
_corked = false;
}
// do not overwrite FETTec simulation's ESC telemetry data:
SITL::SITL *sitl = AP::sitl();
if (sitl != nullptr &&
sitl->fetteconewireesc_sim.enabled()) {
return;
}
if (esc_telem == nullptr) {
esc_telem = new AP_ESC_Telem_SITL;
}

View File

@ -367,6 +367,9 @@ int SITL_State::sim_fd(const char *name, const char *arg)
} else if (streq(name, "richenpower")) {
sitl_model->set_richenpower(&_sitl->richenpower_sim);
return _sitl->richenpower_sim.fd();
} else if (streq(name, "fetteconewireesc")) {
sitl_model->set_fetteconewireesc(&_sitl->fetteconewireesc_sim);
return _sitl->fetteconewireesc_sim.fd();
} else if (streq(name, "ie24")) {
sitl_model->set_ie24(&_sitl->ie24_sim);
return _sitl->ie24_sim.fd();
@ -490,6 +493,8 @@ int SITL_State::sim_fd_write(const char *name)
return sf45b->write_fd();
} else if (streq(name, "richenpower")) {
return _sitl->richenpower_sim.write_fd();
} else if (streq(name, "fetteconewireesc")) {
return _sitl->fetteconewireesc_sim.write_fd();
} else if (streq(name, "ie24")) {
return _sitl->ie24_sim.write_fd();
} else if (streq(name, "gyus42v2")) {
@ -814,6 +819,23 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
}
}
if (_sitl != nullptr) {
// FETtec ESC simulation support. Input signals of 1000-2000
// are positive thrust, 0 to 1000 are negative thrust. Deeper
// changes required to support negative thrust - potentially
// adding a field to input.
if (_sitl != nullptr) {
if (_sitl->fetteconewireesc_sim.enabled()) {
_sitl->fetteconewireesc_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]);
}
}
}
}
}
float engine_mul = _sitl?_sitl->engine_mul.get():1;
uint8_t engine_fail = _sitl?_sitl->engine_fail.get():0;
float throttle = 0.0f;

View File

@ -54,6 +54,7 @@
#include <SITL/SIM_PS_LightWare_SF45B.h>
#include <SITL/SIM_RichenPower.h>
#include <SITL/SIM_FETtecOneWireESC.h>
#include <AP_HAL/utility/Socket.h>
class HAL_SITL;
@ -298,6 +299,9 @@ private:
// simulated RPLidarA2:
SITL::PS_RPLidarA2 *rplidara2;
// simulated FETtec OneWire ESCs:
SITL::FETtecOneWireESC *fetteconewireesc;
// simulated SF45B proximity sensor:
SITL::PS_LightWare_SF45B *sf45b;