mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 18:14:19 -03:00
Copter: add ADSB_streamrate
This commit is contained in:
parent
07b22dc6eb
commit
66d4caeeb0
@ -740,6 +740,11 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
|||||||
case MSG_MAG_CAL_REPORT:
|
case MSG_MAG_CAL_REPORT:
|
||||||
copter.compass.send_mag_cal_report(chan);
|
copter.compass.send_mag_cal_report(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_ADSB_VEHICLE:
|
||||||
|
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
||||||
|
copter.adsb.send_adsb_vehicle(chan);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
@ -827,6 +832,15 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 0),
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 0),
|
||||||
|
|
||||||
|
// @Param: ADSB
|
||||||
|
// @DisplayName: ADSB stream rate to ground station
|
||||||
|
// @Description: ADSB stream rate to ground station
|
||||||
|
// @Units: Hz
|
||||||
|
// @Range: 0 50
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK, streamRates[9], 5),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -933,6 +947,12 @@ GCS_MAVLINK_Copter::data_stream_send(void)
|
|||||||
send_message(MSG_VIBRATION);
|
send_message(MSG_VIBRATION);
|
||||||
send_message(MSG_RPM);
|
send_message(MSG_RPM);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (copter.gcs_out_of_time) return;
|
||||||
|
|
||||||
|
if (stream_trigger(STREAM_ADSB)) {
|
||||||
|
send_message(MSG_ADSB_VEHICLE);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user