Browse Source

Plane: set sys_status motor outputs bit from safety switch

mission-4.1.18
Randy Mackay 11 years ago committed by Andrew Tridgell
parent
commit
7a6b55368e
  1. 7
      ArduPlane/GCS_Mavlink.pde

7
ArduPlane/GCS_Mavlink.pde

@ -178,7 +178,6 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -178,7 +178,6 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
case CRUISE:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; // motor control
break;
case TRAINING:
@ -198,13 +197,17 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -198,13 +197,17 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_YAW_POSITION; // yaw position
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; // altitude control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; // motor control
break;
case INITIALISING:
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: all present sensors healthy except baro, 3D_MAG, GPS, DIFFERNTIAL_PRESSURE. GEOFENCE always defaults to healthy.
control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE |
MAV_SYS_STATUS_SENSOR_3D_MAG |

Loading…
Cancel
Save