diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 6a20cf11b2..3652c20431 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -13,7 +13,6 @@ #include #include #include "../AP_BattMonitor/AP_BattMonitor.h" -#include #include // GCS Message ID's @@ -193,7 +192,7 @@ public: void send_ahrs2(AP_AHRS &ahrs); bool send_gps_raw(AP_GPS &gps); void send_system_time(AP_GPS &gps); - void send_radio_in(const RCMapper &rcmap, uint8_t receiver_rssi); + void send_radio_in(uint8_t receiver_rssi); void send_raw_imu(const AP_InertialSensor &ins, const Compass &compass); void send_scaled_pressure(AP_Baro &barometer); void send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 67bb8487a7..45464586b0 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -981,7 +981,7 @@ void GCS_MAVLINK::send_system_time(AP_GPS &gps) /* send RC_CHANNELS_RAW, and RC_CHANNELS messages */ -void GCS_MAVLINK::send_radio_in(const RCMapper &rcmap, uint8_t receiver_rssi) +void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi) { uint32_t now = hal.scheduler->millis(); @@ -993,10 +993,10 @@ void GCS_MAVLINK::send_radio_in(const RCMapper &rcmap, uint8_t receiver_rssi) chan, now, 0, // port - values[rcmap.roll()-1], - values[rcmap.pitch()-1], - values[rcmap.throttle()-1], - values[rcmap.yaw()-1], + values[0], + values[1], + values[2], + values[3], values[4], values[5], values[6],