Browse Source

GCS_MAVLink: removed deprecated RC_CHANNELS_RAW and use RC_CHANNELS only

mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
53260969bb
  1. 46
      libraries/GCS_MAVLink/GCS_Common.cpp

46
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1102,14 +1102,14 @@ void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi)
{ {
uint32_t now = AP_HAL::millis(); uint32_t now = AP_HAL::millis();
uint16_t values[8]; uint16_t values[18];
memset(values, 0, sizeof(values)); memset(values, 0, sizeof(values));
hal.rcin->read(values, 8); hal.rcin->read(values, 18);
mavlink_msg_rc_channels_raw_send( mavlink_msg_rc_channels_send(
chan, chan,
now, now,
0, // port hal.rcin->num_channels(),
values[0], values[0],
values[1], values[1],
values[2], values[2],
@ -1118,33 +1118,17 @@ void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi)
values[5], values[5],
values[6], values[6],
values[7], values[7],
receiver_rssi); values[8],
values[9],
if (hal.rcin->num_channels() > 8 && HAVE_PAYLOAD_SPACE(chan, RC_CHANNELS)) { values[10],
mavlink_msg_rc_channels_send( values[11],
chan, values[12],
now, values[13],
hal.rcin->num_channels(), values[14],
hal.rcin->read(CH_1), values[15],
hal.rcin->read(CH_2), values[16],
hal.rcin->read(CH_3), values[17],
hal.rcin->read(CH_4), receiver_rssi);
hal.rcin->read(CH_5),
hal.rcin->read(CH_6),
hal.rcin->read(CH_7),
hal.rcin->read(CH_8),
hal.rcin->read(CH_9),
hal.rcin->read(CH_10),
hal.rcin->read(CH_11),
hal.rcin->read(CH_12),
hal.rcin->read(CH_13),
hal.rcin->read(CH_14),
hal.rcin->read(CH_15),
hal.rcin->read(CH_16),
hal.rcin->read(CH_17),
hal.rcin->read(CH_18),
receiver_rssi);
}
} }
void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &compass) void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &compass)

Loading…
Cancel
Save