mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: add microseconds since boot to the home and origin Mavlink messages
This commit is contained in:
parent
479d4be3fd
commit
f6ab044161
|
@ -1474,7 +1474,8 @@ void GCS_MAVLINK::send_home(const Location &home) const
|
|||
home.alt * 10,
|
||||
0.0f, 0.0f, 0.0f,
|
||||
q,
|
||||
0.0f, 0.0f, 0.0f);
|
||||
0.0f, 0.0f, 0.0f,
|
||||
AP_HAL::micros64());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1485,7 +1486,8 @@ void GCS_MAVLINK::send_ekf_origin(const Location &ekf_origin) const
|
|||
chan,
|
||||
ekf_origin.lat,
|
||||
ekf_origin.lng,
|
||||
ekf_origin.alt * 10);
|
||||
ekf_origin.alt * 10,
|
||||
AP_HAL::micros64());
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue