mavlink_messages: fill in all 16 servo channels

This commit is contained in:
Beat Küng 2018-06-04 10:00:13 +02:00
parent eb188996d0
commit 5f87545e48

View File

@ -2349,6 +2349,8 @@ protected:
if (_act_sub->update(&_act_time, &act)) {
mavlink_servo_output_raw_t msg = {};
static_assert(sizeof(act.output) / sizeof(act.output[0]) >= 16, "mavlink message requires at least 16 outputs");
msg.time_usec = act.timestamp;
msg.port = N;
msg.servo1_raw = act.output[0];
@ -2359,6 +2361,14 @@ protected:
msg.servo6_raw = act.output[5];
msg.servo7_raw = act.output[6];
msg.servo8_raw = act.output[7];
msg.servo9_raw = act.output[8];
msg.servo10_raw = act.output[9];
msg.servo11_raw = act.output[10];
msg.servo12_raw = act.output[11];
msg.servo13_raw = act.output[12];
msg.servo14_raw = act.output[13];
msg.servo15_raw = act.output[14];
msg.servo16_raw = act.output[15];
mavlink_msg_servo_output_raw_send_struct(_mavlink->get_channel(), &msg);