Merge pull request #1505 from mhkabir/timesync

Timesync
This commit is contained in:
Lorenz Meier
2015-01-04 11:41:44 +01:00
4 changed files with 189 additions and 2 deletions
+2
View File
@@ -1419,6 +1419,8 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("DISTANCE_SENSOR", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("VFR_HUD", 10.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("TIMESYNC", 10.0f);
break;
default:
+88
View File
@@ -923,6 +923,92 @@ protected:
}
};
class MavlinkStreamSystemTime : public MavlinkStream
{
public:
const char *get_name() const {
return MavlinkStreamSystemTime::get_name_static();
}
static const char *get_name_static() {
return "SYSTEM_TIME";
}
uint8_t get_id() {
return MAVLINK_MSG_ID_SYSTEM_TIME;
}
static MavlinkStream *new_instance(Mavlink *mavlink) {
return new MavlinkStreamSystemTime(mavlink);
}
unsigned get_size() {
return MAVLINK_MSG_ID_SYSTEM_TIME_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
/* do not allow top copying this class */
MavlinkStreamSystemTime(MavlinkStreamSystemTime &);
MavlinkStreamSystemTime &operator = (const MavlinkStreamSystemTime &);
protected:
explicit MavlinkStreamSystemTime(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
void send(const hrt_abstime t) {
mavlink_system_time_t msg;
timespec tv;
clock_gettime(CLOCK_REALTIME, &tv);
msg.time_boot_ms = hrt_absolute_time() / 1000;
msg.time_unix_usec = (uint64_t)tv.tv_sec * 1000000 + tv.tv_nsec / 1000;
_mavlink->send_message(MAVLINK_MSG_ID_SYSTEM_TIME, &msg);
}
};
class MavlinkStreamTimesync : public MavlinkStream
{
public:
const char *get_name() const {
return MavlinkStreamTimesync::get_name_static();
}
static const char *get_name_static() {
return "TIMESYNC";
}
uint8_t get_id() {
return MAVLINK_MSG_ID_TIMESYNC;
}
static MavlinkStream *new_instance(Mavlink *mavlink) {
return new MavlinkStreamTimesync(mavlink);
}
unsigned get_size() {
return MAVLINK_MSG_ID_TIMESYNC_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
/* do not allow top copying this class */
MavlinkStreamTimesync(MavlinkStreamTimesync &);
MavlinkStreamTimesync &operator = (const MavlinkStreamTimesync &);
protected:
explicit MavlinkStreamTimesync(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
void send(const hrt_abstime t) {
mavlink_timesync_t msg;
msg.tc1 = 0;
msg.ts1 = hrt_absolute_time() * 1000; // boot time in nanoseconds
_mavlink->send_message(MAVLINK_MSG_ID_TIMESYNC, &msg);
}
};
class MavlinkStreamGlobalPositionInt : public MavlinkStream
{
@@ -2197,6 +2283,8 @@ StreamListItem *streams_list[] = {
new StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static),
new StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static),
new StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static),
new StreamListItem(&MavlinkStreamSystemTime::new_instance, &MavlinkStreamSystemTime::get_name_static),
new StreamListItem(&MavlinkStreamTimesync::new_instance, &MavlinkStreamTimesync::get_name_static),
new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static),
new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static),
new StreamListItem(&MavlinkStreamViconPositionEstimate::new_instance, &MavlinkStreamViconPositionEstimate::get_name_static),
+86 -2
View File
@@ -123,7 +123,9 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_old_timestamp(0),
_hil_local_proj_inited(0),
_hil_local_alt0(0.0f),
_hil_local_proj_ref{}
_hil_local_proj_ref{},
_time_offset_avg_alpha(0.6),
_time_offset(0)
{
// make sure the FTP server is started
@@ -190,6 +192,14 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
MavlinkFTP::get_server()->handle_message(_mavlink, msg);
break;
case MAVLINK_MSG_ID_SYSTEM_TIME:
handle_message_system_time(msg);
break;
case MAVLINK_MSG_ID_TIMESYNC:
handle_message_timesync(msg);
break;
default:
break;
}
@@ -698,7 +708,7 @@ MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg)
// Use the component ID to identify the vision sensor
vision_position.id = msg->compid;
vision_position.timestamp_boot = hrt_absolute_time();
vision_position.timestamp_boot = to_hrt(pos.usec); // Synced time
vision_position.timestamp_computer = pos.usec;
vision_position.x = pos.x;
vision_position.y = pos.y;
@@ -927,6 +937,63 @@ MavlinkReceiver::handle_message_request_data_stream(mavlink_message_t *msg)
}
}
void
MavlinkReceiver::handle_message_system_time(mavlink_message_t *msg)
{
mavlink_system_time_t time;
mavlink_msg_system_time_decode(msg, &time);
timespec tv;
clock_gettime(CLOCK_REALTIME, &tv);
// date -d @1234567890: Sat Feb 14 02:31:30 MSK 2009
bool onb_unix_valid = tv.tv_sec > 1234567890L;
bool ofb_unix_valid = time.time_unix_usec > 1234567890L * 1000;
if (!onb_unix_valid && ofb_unix_valid) {
tv.tv_sec = time.time_unix_usec / 1000000;
tv.tv_nsec = (time.time_unix_usec % 1000000) * 1000;
clock_settime(CLOCK_REALTIME, &tv);
warnx("[timesync] Set system time from SYSTEM_TIME message");
}
}
void
MavlinkReceiver::handle_message_timesync(mavlink_message_t *msg)
{
mavlink_timesync_t tsync;
mavlink_msg_timesync_decode(msg, &tsync);
uint64_t now_ns = hrt_absolute_time() * 1000 ;
if (tsync.tc1 == 0) {
mavlink_timesync_t rsync; // return timestamped sync message
rsync.tc1 = now_ns;
rsync.ts1 = tsync.ts1;
_mavlink->send_message(MAVLINK_MSG_ID_TIMESYNC, &rsync);
return;
} else if (tsync.tc1 > 0) {
int64_t offset_ns = (9*_time_offset + (tsync.ts1 + now_ns - tsync.tc1*2)/2 )/10; // average offset
int64_t dt = _time_offset - offset_ns;
if (dt > 10000000 || dt < -1000000) { // 10 millisecond skew
_time_offset = (tsync.ts1 + now_ns - tsync.tc1*2)/2;
warnx("[timesync] Companion clock offset is skewed. Hard-setting offset");
} else {
smooth_time_offset(offset_ns);
}
}
}
void
MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
{
@@ -1394,6 +1461,23 @@ void MavlinkReceiver::print_status()
}
uint64_t MavlinkReceiver::to_hrt(uint64_t usec)
{
return usec - (_time_offset / 1000) ;
}
void MavlinkReceiver::smooth_time_offset(uint64_t offset_ns)
{
/* alpha = 0.75 fixed for now. The closer alpha is to 1.0,
* the faster the moving average updates in response to
* new offset samples.
*/
_time_offset = (_time_offset_avg_alpha * offset_ns) + (1.0 - _time_offset_avg_alpha) * _time_offset;
}
void *MavlinkReceiver::start_helper(void *context)
{
MavlinkReceiver *rcv = new MavlinkReceiver((Mavlink *)context);
+13
View File
@@ -124,12 +124,23 @@ private:
void handle_message_manual_control(mavlink_message_t *msg);
void handle_message_heartbeat(mavlink_message_t *msg);
void handle_message_request_data_stream(mavlink_message_t *msg);
void handle_message_system_time(mavlink_message_t *msg);
void handle_message_timesync(mavlink_message_t *msg);
void handle_message_hil_sensor(mavlink_message_t *msg);
void handle_message_hil_gps(mavlink_message_t *msg);
void handle_message_hil_state_quaternion(mavlink_message_t *msg);
void *receive_thread(void *arg);
/**
* Convert remote nsec timestamp to local hrt time (usec)
*/
uint64_t to_hrt(uint64_t nsec);
/**
* Exponential moving average filter to smooth time offset
*/
void smooth_time_offset(uint64_t offset_ns);
mavlink_status_t status;
struct vehicle_local_position_s hil_local_pos;
struct vehicle_control_mode_s _control_mode;
@@ -164,6 +175,8 @@ private:
bool _hil_local_proj_inited;
float _hil_local_alt0;
struct map_projection_reference_s _hil_local_proj_ref;
double _time_offset_avg_alpha;
uint64_t _time_offset;
/* do not allow copying this class */
MavlinkReceiver(const MavlinkReceiver&);