AP_UAVCAN: replace old hardcoded value with new mavlink enum

This commit is contained in:
Tom Pittenger 2020-08-21 09:11:19 -07:00 committed by Tom Pittenger
parent 96a2aa485a
commit b502582d14

View File

@ -800,12 +800,11 @@ void AP_UAVCAN::handle_traffic_report(AP_UAVCAN* ap_uavcan, uint8_t node_id, con
if (msg.simulated_report) {
pkt.flags |= ADSB_FLAGS_SIMULATED;
}
// flags not in common.xml yet
if (msg.vertical_velocity_valid) {
pkt.flags |= 0x80;
pkt.flags |= ADSB_FLAGS_VERTICAL_VELOCITY_VALID;
}
if (msg.baro_valid) {
pkt.flags |= 0x100;
pkt.flags |= ADSB_FLAGS_BARO_VALID;
}
vehicle.last_update_ms = AP_HAL::native_millis() - (vehicle.info.tslc * 1000);