mirror of https://github.com/ArduPilot/ardupilot
SITL: expose home location
This commit is contained in:
parent
57c0551260
commit
47b79eb72d
|
@ -330,6 +330,10 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
|||
smooth_sensors();
|
||||
}
|
||||
fdm.timestamp_us = time_now_us;
|
||||
if (fdm.home.lat == 0 && fdm.home.lng == 0) {
|
||||
// initialise home
|
||||
fdm.home = home;
|
||||
}
|
||||
fdm.latitude = location.lat * 1.0e-7;
|
||||
fdm.longitude = location.lng * 1.0e-7;
|
||||
fdm.altitude = location.alt * 1.0e-2;
|
||||
|
|
|
@ -9,6 +9,7 @@ namespace SITL {
|
|||
struct sitl_fdm {
|
||||
// this is the structure passed between FDM models and the main SITL code
|
||||
uint64_t timestamp_us;
|
||||
Location home;
|
||||
double latitude, longitude; // degrees
|
||||
double altitude; // MSL
|
||||
double heading; // degrees
|
||||
|
|
Loading…
Reference in New Issue