px4io: remove special handling for HITL

In HITL the actuators should not be mapped
and they are in lockdown.

We should not reconfigure disarmed, min, max PWM values
without updating the actual output values because the IO
will consider the last outputs before the FMU was rebooted
with the configuration of the new boot. This can result
in spinning motors when switching to SIH.
This commit is contained in:
Matthias Grob 2024-03-25 19:09:14 +01:00
parent b5f6699f2e
commit de89777b6a
1 changed files with 7 additions and 22 deletions

View File

@ -335,8 +335,7 @@ private:
(ParamInt<px4::params::RC_RSSI_PWM_CHAN>) _param_rc_rssi_pwm_chan,
(ParamInt<px4::params::RC_RSSI_PWM_MAX>) _param_rc_rssi_pwm_max,
(ParamInt<px4::params::RC_RSSI_PWM_MIN>) _param_rc_rssi_pwm_min,
(ParamInt<px4::params::SENS_EN_THERMAL>) _param_sens_en_themal,
(ParamInt<px4::params::SYS_HITL>) _param_sys_hitl
(ParamInt<px4::params::SENS_EN_THERMAL>) _param_sens_en_themal
)
};
@ -474,9 +473,7 @@ int PX4IO::init()
}
/* try to claim the generic PWM output device node as well - it's OK if we fail at this */
if (_param_sys_hitl.get() <= 0) {
_mixing_output.setMaxTopicUpdateRate(MIN_TOPIC_UPDATE_INTERVAL);
}
_mixing_output.setMaxTopicUpdateRate(MIN_TOPIC_UPDATE_INTERVAL);
_px4io_status_pub.advertise();
@ -525,9 +522,7 @@ void PX4IO::Run()
perf_count(_interval_perf);
/* if we have new control data from the ORB, handle it */
if (_param_sys_hitl.get() <= 0) {
_mixing_output.update();
}
_mixing_output.update();
if (hrt_elapsed_time(&_poll_last) >= 20_ms) {
/* run at 50 */
@ -540,13 +535,11 @@ void PX4IO::Run()
io_publish_raw_rc();
}
if (_param_sys_hitl.get() <= 0) {
/* check updates on uORB topics and handle it */
if (_t_actuator_armed.updated()) {
io_set_arming_state();
/* check updates on uORB topics and handle it */
if (_t_actuator_armed.updated()) {
io_set_arming_state();
// TODO: throttle
}
// TODO: throttle
}
if (!_mixing_output.armed().armed) {
@ -814,14 +807,6 @@ PX4IO::io_set_arming_state()
clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
}
// XXX this is for future support in the commander
// but can be removed if unneeded
// if (armed.termination_failsafe) {
// set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
// } else {
// clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
// }
if (armed.ready_to_arm) {
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;