diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-01-26 14:52:46 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-01-26 14:52:46 +0100 |
commit | 9cdbbab855d463bffb39d8dd55888fc1e0423818 (patch) | |
tree | 73ceaaab28d0fd08ea47c02eab66c11638c86e58 /src/modules/mavlink | |
parent | 731ab465b3d7d40ffb5ce3ca3d14660c6fee1ae6 (diff) | |
download | px4-firmware-9cdbbab855d463bffb39d8dd55888fc1e0423818.tar.gz px4-firmware-9cdbbab855d463bffb39d8dd55888fc1e0423818.tar.bz2 px4-firmware-9cdbbab855d463bffb39d8dd55888fc1e0423818.zip |
Differentiate between publication and signal receive timestamp, correctly set the rc_lost flag in the frame. Ready for prime-time testing.
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r-- | src/modules/mavlink/orb_listener.c | 2 |
1 files changed, 1 insertions, 1 deletions
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c index 92b1b45be..41c754405 100644 --- a/src/modules/mavlink/orb_listener.c +++ b/src/modules/mavlink/orb_listener.c @@ -355,7 +355,7 @@ l_input_rc(const struct listener *l) for (unsigned i = 0; (i * port_width) < (rc_raw.channel_count + port_width); i++) { /* Channels are sent in MAVLink main loop at a fixed interval */ mavlink_msg_rc_channels_raw_send(chan, - rc_raw.timestamp / 1000, + rc_raw.timestamp_publication / 1000, i, (rc_raw.channel_count > (i * port_width) + 0) ? rc_raw.values[(i * port_width) + 0] : UINT16_MAX, (rc_raw.channel_count > (i * port_width) + 1) ? rc_raw.values[(i * port_width) + 1] : UINT16_MAX, |