forked from Archive/PX4-Autopilot
mavlink: timesync: readd timesync_status uORB to report Mavlink timesync
This commit is contained in:
parent
250b6b24ab
commit
2568d9ae20
|
@ -169,10 +169,10 @@ bool RtpsTopics::getMsg(const uint8_t topic_ID, eprosima::fastcdr::Cdr &scdr)
|
|||
// apply timestamp offset
|
||||
_timesync->addOffset(msg.timestamp());
|
||||
msg.serialize(scdr);
|
||||
ret = true;
|
||||
@[ if topic == 'Timesync' or topic == 'timesync']@
|
||||
}
|
||||
@[ end if]@
|
||||
ret = true;
|
||||
_@(topic)_sub.unlockMsg();
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -1,10 +1,5 @@
|
|||
uint64 timestamp # time since system start (microseconds)
|
||||
uint8 sys_id # id of the origin system
|
||||
uint8 seq # timesync msg sequence
|
||||
int64 tc1 # time sync timestamp 1
|
||||
int64 ts1 # time sync timestamp 2
|
||||
|
||||
uint64 remote_timestamp # remote system timestamp (microseconds)
|
||||
int64 observed_offset # raw time offset directly observed from this timesync packet (microseconds)
|
||||
int64 estimated_offset # smoothed time offset between companion system and PX4 (microseconds)
|
||||
uint32 round_trip_time # round trip time of this timesync packet (microseconds)
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint8 sys_id # id of the origin system
|
||||
uint8 seq # timesync msg sequence
|
||||
int64 tc1 # time sync timestamp 1
|
||||
int64 ts1 # time sync timestamp 2
|
||||
|
|
|
@ -0,0 +1,5 @@
|
|||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 remote_timestamp # remote system timestamp (microseconds)
|
||||
int64 observed_offset # raw time offset directly observed from this timesync packet (microseconds)
|
||||
int64 estimated_offset # smoothed time offset between companion system and PX4 (microseconds)
|
||||
uint32 round_trip_time # round trip time of this timesync packet (microseconds)
|
|
@ -291,6 +291,8 @@ rtps:
|
|||
id: 129
|
||||
- msg: vehicle_trajectory_bezier
|
||||
id: 130
|
||||
- msg: timesync_status
|
||||
id: 131
|
||||
########## multi topics: begin ##########
|
||||
- msg: actuator_controls_0
|
||||
id: 150
|
||||
|
|
|
@ -138,7 +138,7 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg)
|
|||
}
|
||||
|
||||
// Publish status message
|
||||
timesync_s tsync_status{};
|
||||
timesync_status_s tsync_status{};
|
||||
|
||||
tsync_status.timestamp = hrt_absolute_time();
|
||||
tsync_status.remote_timestamp = tsync.tc1 / 1000ULL;
|
||||
|
@ -146,7 +146,7 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg)
|
|||
tsync_status.estimated_offset = (int64_t)_time_offset;
|
||||
tsync_status.round_trip_time = rtt_us;
|
||||
|
||||
_timesync_pub.publish(tsync_status);
|
||||
_timesync_status_pub.publish(tsync_status);
|
||||
}
|
||||
|
||||
break;
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include "mavlink_bridge_header.h"
|
||||
|
||||
#include <uORB/PublicationMulti.hpp>
|
||||
#include <uORB/topics/timesync.h>
|
||||
#include <uORB/topics/timesync_status.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
|
@ -132,7 +132,7 @@ protected:
|
|||
*/
|
||||
void reset_filter();
|
||||
|
||||
uORB::PublicationMulti<timesync_s> _timesync_pub{ORB_ID(timesync)};
|
||||
uORB::PublicationMulti<timesync_status_s> _timesync_status_pub{ORB_ID(timesync_status)};
|
||||
|
||||
uint32_t _sequence{0};
|
||||
|
||||
|
|
Loading…
Reference in New Issue