AP_GPS: Remove unneeded wrappers

This commit is contained in:
Michael du Breuil 2019-04-20 14:54:21 -07:00 committed by Andrew Tridgell
parent e177db7dcd
commit e6d97f63a5
2 changed files with 2 additions and 18 deletions

View File

@ -965,8 +965,8 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
ground_speed(1)*100, // cm/s
ground_course(1)*100, // 1/100 degrees,
num_sats(1),
rtk_num_sats(1),
rtk_age_ms(1));
state[1].rtk_num_sats,
state[1].rtk_age_ms);
}
void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)

View File

@ -329,22 +329,6 @@ public:
return have_vertical_velocity(primary_instance);
}
// return number of satellites used for RTK calculation
uint8_t rtk_num_sats(uint8_t instance) const {
return state[instance].rtk_num_sats;
}
uint8_t rtk_num_sats(void) const {
return rtk_num_sats(primary_instance);
}
// return age of last baseline correction in milliseconds
uint32_t rtk_age_ms(uint8_t instance) const {
return state[instance].rtk_age_ms;
}
uint32_t rtk_age_ms(void) const {
return rtk_age_ms(primary_instance);
}
// the expected lag (in seconds) in the position and velocity readings from the gps
// return true if the GPS hardware configuration is known or the lag parameter has been set manually
bool get_lag(uint8_t instance, float &lag_sec) const;