AP_GPS: Replace hardcoded duplicated end_mavlink_gps*_rtk() function with a flexible one

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-06-30 15:45:24 +02:00 committed by Francisco Ferreira
parent 84e5cd7e14
commit 430b863f42
3 changed files with 7 additions and 14 deletions

View File

@ -926,17 +926,13 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
rtk_age_ms(1));
}
void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan)
void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
{
if (drivers[0] != nullptr && drivers[0]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) {
drivers[0]->send_mavlink_gps_rtk(chan);
if (inst >= GPS_MAX_RECEIVERS) {
return;
}
}
void AP_GPS::send_mavlink_gps2_rtk(mavlink_channel_t chan)
{
if (drivers[1] != nullptr && drivers[1]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) {
drivers[1]->send_mavlink_gps_rtk(chan);
if (drivers[inst] != nullptr && drivers[inst]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) {
drivers[inst]->send_mavlink_gps_rtk(chan);
}
}

View File

@ -363,8 +363,7 @@ public:
void send_mavlink_gps_raw(mavlink_channel_t chan);
void send_mavlink_gps2_raw(mavlink_channel_t chan);
void send_mavlink_gps_rtk(mavlink_channel_t chan);
void send_mavlink_gps2_rtk(mavlink_channel_t chan);
void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst);
// Returns the index of the first unconfigured GPS (returns GPS_ALL_CONFIGURED if all instances report as being configured)
uint8_t first_unconfigured_gps(void) const;

View File

@ -44,9 +44,7 @@ public:
virtual void inject_data(const uint8_t *data, uint16_t len);
//MAVLink methods
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan) { return ; }
virtual void send_mavlink_gps2_rtk(mavlink_channel_t chan) { return ; }
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan);
virtual void broadcast_configuration_failure_reason(void) const { return ; }