GCS_MAVLink: send radio_in using rcmap

This commit is contained in:
Randy Mackay 2014-08-16 15:27:03 +09:00
parent 5b114dcad5
commit 0881ccbee0
2 changed files with 7 additions and 6 deletions

View File

@ -13,6 +13,7 @@
#include <DataFlash.h>
#include <AP_Mission.h>
#include "../AP_BattMonitor/AP_BattMonitor.h"
#include <AP_RCMapper.h>
#include <stdint.h>
// GCS Message ID's
@ -192,7 +193,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(uint8_t receiver_rssi);
void send_radio_in(const RCMapper &rcmap, 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);

View File

@ -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(uint8_t receiver_rssi)
void GCS_MAVLINK::send_radio_in(const RCMapper &rcmap, uint8_t receiver_rssi)
{
uint32_t now = hal.scheduler->millis();
@ -993,10 +993,10 @@ void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi)
chan,
now,
0, // port
values[0],
values[1],
values[2],
values[3],
values[rcmap.roll()-1],
values[rcmap.pitch()-1],
values[rcmap.throttle()-1],
values[rcmap.yaw()-1],
values[4],
values[5],
values[6],