aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorM.H.Kabir <mhkabir98@gmail.com>2015-01-04 21:29:05 +0530
committerM.H.Kabir <mhkabir98@gmail.com>2015-01-04 21:29:05 +0530
commitc47e8c22688ad3ac358c71337ef8cb0feeeba409 (patch)
tree12d65880431a684396a4ac2f54b6f66cd0899485 /src
parent9fdbdee03ea1eaf6b15059c7a7c16574df8d6cbf (diff)
downloadpx4-firmware-c47e8c22688ad3ac358c71337ef8cb0feeeba409.tar.gz
px4-firmware-c47e8c22688ad3ac358c71337ef8cb0feeeba409.tar.bz2
px4-firmware-c47e8c22688ad3ac358c71337ef8cb0feeeba409.zip
Add suffixes, constant
Diffstat (limited to 'src')
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp16
-rw-r--r--src/modules/mavlink/mavlink_receiver.h2
2 files changed, 12 insertions, 6 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 9b3274431..d84b70e46 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -947,14 +947,18 @@ MavlinkReceiver::handle_message_system_time(mavlink_message_t *msg)
clock_gettime(CLOCK_REALTIME, &tv);
// date -d @1234567890: Sat Feb 14 02:31:30 MSK 2009
- bool onb_unix_valid = tv.tv_sec > 1234567890ULL;
- bool ofb_unix_valid = time.time_unix_usec > 1234567890ULL * 1000ULL;
+ bool onb_unix_valid = tv.tv_sec > PX4_EPOCH_SECS;
+ bool ofb_unix_valid = time.time_unix_usec > PX4_EPOCH_SECS * 1000ULL;
if (!onb_unix_valid && ofb_unix_valid) {
tv.tv_sec = time.time_unix_usec / 1000000ULL;
tv.tv_nsec = (time.time_unix_usec % 1000000ULL) * 1000ULL;
- clock_settime(CLOCK_REALTIME, &tv);
- warnx("[timesync] synced..");
+ if(clock_settime(CLOCK_REALTIME, &tv)) {
+ warn("failed setting clock");
+ }
+ else {
+ warnx("[timesync] UTC time synced.");
+ }
}
}
@@ -983,9 +987,9 @@ MavlinkReceiver::handle_message_timesync(mavlink_message_t *msg)
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 < -10000000) { // 10 millisecond skew
+ if (dt > 10000000LL || dt < -10000000LL) { // 10 millisecond skew
_time_offset = (tsync.ts1 + now_ns - tsync.tc1*2)/2;
- warnx("[timesync] Resetting.");
+ warnx("[timesync] Resetting offset sync.");
} else {
smooth_time_offset(offset_ns);
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index a677e75cd..4afc9b372 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -75,6 +75,8 @@
#include "mavlink_ftp.h"
+#define PX4_EPOCH_SECS 1234567890ULL
+
class Mavlink;
class MavlinkReceiver