mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
HAL_SITL: enable ADSB simulator in SITL periph
This commit is contained in:
parent
92c0e7f860
commit
bf229b3dc1
@ -270,6 +270,12 @@ void SimMCast::multicast_read(void)
|
||||
base_time_us += (_sitl->state.timestamp_us - state.timestamp_us);
|
||||
}
|
||||
_sitl->state = state;
|
||||
location.lat = state.latitude*1.0e7;
|
||||
location.lng = state.longitude*1.0e7;
|
||||
location.alt = state.altitude*1.0e2;
|
||||
if (home.is_zero()) {
|
||||
home = location;
|
||||
}
|
||||
hal.scheduler->stop_clock(_sitl->state.timestamp_us + base_time_us);
|
||||
HALSITL::Scheduler::timer_event();
|
||||
if (servo_fd == -1) {
|
||||
|
@ -66,7 +66,7 @@ public:
|
||||
"none:0",
|
||||
"GPS1",
|
||||
"none:1",
|
||||
"none:2",
|
||||
"sim:adsb",
|
||||
"none:3",
|
||||
"none:4",
|
||||
"none:5",
|
||||
|
Loading…
Reference in New Issue
Block a user