aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-01-26 14:52:46 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-01-26 14:52:46 +0100
commit9cdbbab855d463bffb39d8dd55888fc1e0423818 (patch)
tree73ceaaab28d0fd08ea47c02eab66c11638c86e58 /src/modules
parent731ab465b3d7d40ffb5ce3ca3d14660c6fee1ae6 (diff)
downloadpx4-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')
-rw-r--r--src/modules/mavlink/orb_listener.c2
-rw-r--r--src/modules/sensors/sensors.cpp9
2 files changed, 7 insertions, 4 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,
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 23f20b0cb..df6cbb7b2 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -1276,6 +1276,9 @@ Sensors::rc_poll()
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
+ if (rc_input.rc_lost)
+ return;
+
struct manual_control_setpoint_s manual_control;
struct actuator_controls_s actuator_group_3;
@@ -1320,7 +1323,7 @@ Sensors::rc_poll()
channel_limit = _rc_max_chan_count;
/* we are accepting this message */
- _rc_last_valid = rc_input.timestamp;
+ _rc_last_valid = rc_input.timestamp_last_signal;
/* Read out values from raw message */
for (unsigned int i = 0; i < channel_limit; i++) {
@@ -1369,9 +1372,9 @@ Sensors::rc_poll()
}
_rc.chan_count = rc_input.channel_count;
- _rc.timestamp = rc_input.timestamp;
+ _rc.timestamp = rc_input.timestamp_last_signal;
- manual_control.timestamp = rc_input.timestamp;
+ manual_control.timestamp = rc_input.timestamp_last_signal;
/* roll input - rolling right is stick-wise and rotation-wise positive */
manual_control.roll = limit_minus_one_to_one(_rc.chan[_rc.function[ROLL]].scaled);