diff options
author | Anton Babushkin <anton.babushkin@me.com> | 2014-01-02 14:51:48 +0400 |
---|---|---|
committer | Anton Babushkin <anton.babushkin@me.com> | 2014-01-02 14:51:48 +0400 |
commit | 6a5d5f7136c8f317594bcc768131fe1779eabf2c (patch) | |
tree | 303002956bc8eec7cbb31878bb627f81194985a5 /src/modules/mavlink | |
parent | 74e2542c07ffc154139ea12d722e5396b083f308 (diff) | |
parent | b345202ae7f4af749d5779943fcfed258f2efbbd (diff) | |
download | px4-firmware-6a5d5f7136c8f317594bcc768131fe1779eabf2c.tar.gz px4-firmware-6a5d5f7136c8f317594bcc768131fe1779eabf2c.tar.bz2 px4-firmware-6a5d5f7136c8f317594bcc768131fe1779eabf2c.zip |
Merge master into navigator_new
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r-- | src/modules/mavlink/orb_listener.c | 37 |
1 files changed, 22 insertions, 15 deletions
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c index e168dded3..6e177bc4d 100644 --- a/src/modules/mavlink/orb_listener.c +++ b/src/modules/mavlink/orb_listener.c @@ -350,20 +350,26 @@ l_input_rc(const struct listener *l) /* copy rc channels into local buffer */ orb_copy(ORB_ID(input_rc), mavlink_subs.input_rc_sub, &rc_raw); - if (gcs_link) - /* Channels are sent in MAVLink main loop at a fixed interval */ - mavlink_msg_rc_channels_raw_send(chan, - rc_raw.timestamp / 1000, - 0, - (rc_raw.channel_count > 0) ? rc_raw.values[0] : UINT16_MAX, - (rc_raw.channel_count > 1) ? rc_raw.values[1] : UINT16_MAX, - (rc_raw.channel_count > 2) ? rc_raw.values[2] : UINT16_MAX, - (rc_raw.channel_count > 3) ? rc_raw.values[3] : UINT16_MAX, - (rc_raw.channel_count > 4) ? rc_raw.values[4] : UINT16_MAX, - (rc_raw.channel_count > 5) ? rc_raw.values[5] : UINT16_MAX, - (rc_raw.channel_count > 6) ? rc_raw.values[6] : UINT16_MAX, - (rc_raw.channel_count > 7) ? rc_raw.values[7] : UINT16_MAX, - 255); + if (gcs_link) { + + const unsigned port_width = 8; + + 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, + 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, + (rc_raw.channel_count > (i * port_width) + 2) ? rc_raw.values[(i * port_width) + 2] : UINT16_MAX, + (rc_raw.channel_count > (i * port_width) + 3) ? rc_raw.values[(i * port_width) + 3] : UINT16_MAX, + (rc_raw.channel_count > (i * port_width) + 4) ? rc_raw.values[(i * port_width) + 4] : UINT16_MAX, + (rc_raw.channel_count > (i * port_width) + 5) ? rc_raw.values[(i * port_width) + 5] : UINT16_MAX, + (rc_raw.channel_count > (i * port_width) + 6) ? rc_raw.values[(i * port_width) + 6] : UINT16_MAX, + (rc_raw.channel_count > (i * port_width) + 7) ? rc_raw.values[(i * port_width) + 7] : UINT16_MAX, + rc_raw.rssi); + } + } } void @@ -492,7 +498,8 @@ l_actuator_outputs(const struct listener *l) if (gcs_link) { mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, - l->arg /* port number */, + l->arg /* port number - needs GCS support */, + /* QGC has port number support already */ act_outputs.output[0], act_outputs.output[1], act_outputs.output[2], |