mirror of https://github.com/ArduPilot/ardupilot
SITL: change ADSB_VEHICLE update rate to 1Hz instead of 2Hz to match PING behavior
This commit is contained in:
parent
52fcc36249
commit
c3b241ca88
|
@ -187,7 +187,7 @@ void ADSB::send_report(void)
|
|||
send a ADSB_VEHICLE messages
|
||||
*/
|
||||
uint32_t now_us = AP_HAL::micros();
|
||||
if (now_us - last_report_us > reporting_period_ms*1000UL) {
|
||||
if (now_us - last_report_us >= reporting_period_ms*1000UL) {
|
||||
for (uint8_t i=0; i<num_vehicles; i++) {
|
||||
ADSB_Vehicle &vehicle = vehicles[i];
|
||||
Location loc = home;
|
||||
|
|
|
@ -57,7 +57,7 @@ private:
|
|||
ADSB_Vehicle vehicles[num_vehicles_MAX];
|
||||
|
||||
// reporting period in ms
|
||||
const float reporting_period_ms = 500;
|
||||
const float reporting_period_ms = 1000;
|
||||
uint32_t last_report_us = 0;
|
||||
uint32_t last_update_us = 0;
|
||||
|
||||
|
|
Loading…
Reference in New Issue