mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-20 11:23:06 +08:00
Commander: remove HIL_STATE_ON from arming lockdown
Removing this from the boolean allows users to send pwm values in SIH.
This commit is contained in:
@@ -1895,8 +1895,7 @@ void Commander::run()
|
||||
_actuator_armed.armed = isArmed();
|
||||
_actuator_armed.prearmed = getPrearmState();
|
||||
_actuator_armed.ready_to_arm = _vehicle_status.pre_flight_checks_pass || isArmed();
|
||||
_actuator_armed.lockdown = ((_vehicle_status.hil_state == vehicle_status_s::HIL_STATE_ON)
|
||||
|| _multicopter_throw_launch.isThrowLaunchInProgress());
|
||||
_actuator_armed.lockdown = _multicopter_throw_launch.isThrowLaunchInProgress();
|
||||
// _actuator_armed.kill // action_request_s::ACTION_KILL
|
||||
_actuator_armed.termination = (_vehicle_status.nav_state == _vehicle_status.NAVIGATION_STATE_TERMINATION);
|
||||
// _actuator_armed.in_esc_calibration_mode // VEHICLE_CMD_PREFLIGHT_CALIBRATION
|
||||
|
||||
Reference in New Issue
Block a user