mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_ADSB: run dynamic at 5Hz and static/cfg at 5sec
This commit is contained in:
parent
ea0a5c973c
commit
8b9057f23c
@ -219,13 +219,13 @@ void AP_ADSB::update(void)
|
|||||||
// haven't gotten a heartbeat health status packet in a while, assume hardware failure
|
// haven't gotten a heartbeat health status packet in a while, assume hardware failure
|
||||||
out_state.chan = -1;
|
out_state.chan = -1;
|
||||||
} else {
|
} else {
|
||||||
if (now - out_state.last_config_ms >= 10000) {
|
if (now - out_state.last_config_ms >= 5000) {
|
||||||
out_state.last_config_ms = now;
|
out_state.last_config_ms = now;
|
||||||
send_configure((mavlink_channel_t)(MAVLINK_COMM_0 + out_state.chan));
|
send_configure((mavlink_channel_t)(MAVLINK_COMM_0 + out_state.chan));
|
||||||
} // last_config_ms
|
} // last_config_ms
|
||||||
|
|
||||||
// send dynamic data to transceiver, every 1s
|
// send dynamic data to transceiver at 5Hz
|
||||||
if (now - out_state.last_report_ms >= 1000) {
|
if (now - out_state.last_report_ms >= 200) {
|
||||||
out_state.last_report_ms = now;
|
out_state.last_report_ms = now;
|
||||||
send_dynamic_out((mavlink_channel_t)(MAVLINK_COMM_0 + out_state.chan));
|
send_dynamic_out((mavlink_channel_t)(MAVLINK_COMM_0 + out_state.chan));
|
||||||
} // last_report_ms
|
} // last_report_ms
|
||||||
|
Loading…
Reference in New Issue
Block a user