diff options
author | sjwilks <sjwilks@gmail.com> | 2014-08-14 12:38:08 +0200 |
---|---|---|
committer | sjwilks <sjwilks@gmail.com> | 2014-08-14 12:38:08 +0200 |
commit | e9b0ee75015cf3544a3dab2015d7af77f53bd23e (patch) | |
tree | 52ec744c91df8ce202178b810c2cf1c9faefe18d | |
parent | f48b4b0c84f6f10170674c7a584eb4087dac8ca8 (diff) | |
parent | e03c4d4b65d956a90a9e95b35718ebc323ff7539 (diff) | |
download | px4-firmware-e9b0ee75015cf3544a3dab2015d7af77f53bd23e.tar.gz px4-firmware-e9b0ee75015cf3544a3dab2015d7af77f53bd23e.tar.bz2 px4-firmware-e9b0ee75015cf3544a3dab2015d7af77f53bd23e.zip |
Merge pull request #1273 from PX4/rc_fix
Fixed copy & paste error on RC output
-rw-r--r-- | src/modules/mavlink/mavlink_messages.cpp | 8 |
1 files changed, 4 insertions, 4 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index f292605c9..af4d46a36 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1642,10 +1642,10 @@ protected: msg.chan2_raw = (rc.channel_count > (i * port_width) + 1) ? rc.values[(i * port_width) + 1] : UINT16_MAX; msg.chan3_raw = (rc.channel_count > (i * port_width) + 2) ? rc.values[(i * port_width) + 2] : UINT16_MAX; msg.chan4_raw = (rc.channel_count > (i * port_width) + 3) ? rc.values[(i * port_width) + 3] : UINT16_MAX; - msg.chan4_raw = (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX; - msg.chan4_raw = (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX; - msg.chan4_raw = (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX; - msg.chan4_raw = (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX; + msg.chan5_raw = (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX; + msg.chan6_raw = (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX; + msg.chan7_raw = (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX; + msg.chan8_raw = (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX; msg.rssi = rc.rssi; _mavlink->send_message(MAVLINK_MSG_ID_RC_CHANNELS_RAW, &msg); |