aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-01-28 11:11:34 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-01-28 11:13:37 +0100
commit19c3525f58b4123c38592644252226219ddef07a (patch)
treee2dd7079488d6e89a25bb82725df2c3f75d14118 /src/modules/mavlink
parent8149bf95fc7882c259196bb171acfa418d21467a (diff)
downloadpx4-firmware-19c3525f58b4123c38592644252226219ddef07a.tar.gz
px4-firmware-19c3525f58b4123c38592644252226219ddef07a.tar.bz2
px4-firmware-19c3525f58b4123c38592644252226219ddef07a.zip
Hotfix: Fixed telemetry transmission of RC channels - we always sent one set too much - by lieron
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/orb_listener.c2
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..192c8fdba 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -352,7 +352,7 @@ l_input_rc(const struct listener *l)
const unsigned port_width = 8;
- for (unsigned i = 0; (i * port_width) < (rc_raw.channel_count + port_width); i++) {
+ for (unsigned i = 0; (i * port_width) < rc_raw.channel_count; i++) {
/* Channels are sent in MAVLink main loop at a fixed interval */
mavlink_msg_rc_channels_raw_send(chan,
rc_raw.timestamp / 1000,