mavlink_receiver: parse all 18 channels from rc_override

This commit is contained in:
MaEtUgR 2018-06-28 20:01:13 +02:00 committed by Beat Küng
parent 4f0e090e88
commit 2c7c876c38
1 changed files with 24 additions and 32 deletions

View File

@ -1821,51 +1821,43 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg)
return;
}
// fill uORB message
struct input_rc_s rc = {};
// metadata
rc.timestamp = hrt_absolute_time();
rc.timestamp_last_signal = rc.timestamp;
rc.channel_count = 8;
rc.rc_failsafe = false;
rc.rc_lost = false;
rc.rc_lost_frame_count = 0;
rc.rc_total_frame_count = 1;
rc.rc_ppm_frame_length = 0;
rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK;
rc.channel_count = 18;
rc.rssi = RC_INPUT_RSSI_MAX;
/* channels */
rc.rc_failsafe = false;
rc.rc_lost = false;
rc.rc_lost_frame_count = 0;
rc.rc_total_frame_count = 1;
rc.rc_ppm_frame_length = 0;
rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK;
// channels
rc.values[0] = man.chan1_raw;
rc.values[1] = man.chan2_raw;
rc.values[2] = man.chan3_raw;
rc.values[3] = man.chan4_raw;
rc.values[4] = man.chan5_raw;
rc.values[5] = man.chan6_raw;
rc.values[6] = man.chan7_raw;
rc.values[7] = man.chan8_raw;
rc.values[8] = man.chan9_raw;
rc.values[9] = man.chan10_raw;
rc.values[10] = man.chan11_raw;
rc.values[11] = man.chan12_raw;
rc.values[12] = man.chan13_raw;
rc.values[13] = man.chan14_raw;
rc.values[14] = man.chan15_raw;
rc.values[15] = man.chan16_raw;
rc.values[16] = man.chan17_raw;
rc.values[17] = man.chan18_raw;
if (_rc_pub == nullptr) {
_rc_pub = orb_advertise(ORB_ID(input_rc), &rc);
} else {
orb_publish(ORB_ID(input_rc), _rc_pub, &rc);
}
// publish uORB message
int instance; // provides the instance ID or the publication
ORB_PRIO priority = ORB_PRIO_HIGH; // since it is an override, set priority high
orb_publish_auto(ORB_ID(input_rc), &_rc_pub, &rc, &instance, priority);
}
void