Rover: Including the sonar/rangefinder status in SYS_STATUS message

This commit is contained in:
Grant Morphett 2015-08-12 12:42:35 +10:00 committed by Randy Mackay
parent 0218e4ac86
commit 4e568ab547

View File

@ -169,6 +169,16 @@ void Rover::send_extended_status1(mavlink_channel_t chan)
battery_current = battery.current_amps() * 100;
}
if (sonar.num_sensors() > 0) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
if (g.sonar_trigger_cm > 0) {
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
}
if (sonar.has_data()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
}
}
if (AP_Notify::flags.initialising) {
// while initialising the gyros and accels are not enabled
control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);