mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: set sys_status motor outputs bit from safety switch
This commit is contained in:
parent
9f3803052f
commit
9bcf9a31ed
@ -161,8 +161,10 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
}
|
||||
|
||||
// all present sensors enabled by default except altitude and position control which we will set individually
|
||||
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL & ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL);
|
||||
// all present sensors enabled by default except altitude and position control and motors which we will set individually
|
||||
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL &
|
||||
~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL &
|
||||
~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS);
|
||||
|
||||
switch (control_mode) {
|
||||
case ALT_HOLD:
|
||||
@ -182,6 +184,11 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
||||
break;
|
||||
}
|
||||
|
||||
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
|
||||
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
|
||||
}
|
||||
|
||||
// default to all healthy except baro, compass, gps and receiver which we set individually
|
||||
control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE |
|
||||
MAV_SYS_STATUS_SENSOR_3D_MAG |
|
||||
|
Loading…
Reference in New Issue
Block a user