mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
GCS_MAVLink: fix ATT_POS_MOCAP timestamp handle
This commit is contained in:
parent
d3da8f2914
commit
0d2b70e607
@ -2171,7 +2171,8 @@ void GCS_MAVLINK::handle_att_pos_mocap(mavlink_message_t *msg)
|
|||||||
Quaternion attitude = Quaternion(m.q);
|
Quaternion attitude = Quaternion(m.q);
|
||||||
const float posErr = 0; // parameter required?
|
const float posErr = 0; // parameter required?
|
||||||
const float angErr = 0; // parameter required?
|
const float angErr = 0; // parameter required?
|
||||||
const uint32_t timestamp_ms = m.time_usec * 0.001;
|
// correct offboard timestamp to be in local ms since boot
|
||||||
|
uint32_t timestamp_ms = correct_offboard_timestamp_usec_to_ms(m.time_usec, PAYLOAD_SIZE(chan, ATT_POS_MOCAP));
|
||||||
const uint32_t reset_timestamp_ms = 0; // no data available
|
const uint32_t reset_timestamp_ms = 0; // no data available
|
||||||
|
|
||||||
AP::ahrs().writeExtNavData(sensor_offset,
|
AP::ahrs().writeExtNavData(sensor_offset,
|
||||||
|
Loading…
Reference in New Issue
Block a user