AP_GPS: remove redundant check

get_type has this sanity check
This commit is contained in:
Peter Barker 2024-03-11 11:29:58 +11:00 committed by Andrew Tridgell
parent 093709cbe3
commit b4f5d49adb

View File

@ -2418,7 +2418,7 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg,
{
#if GPS_MAX_RECEIVERS > 1
const auto type = get_type(instance);
if (instance < GPS_MAX_RECEIVERS &&
if (
((type == GPS_TYPE_UBLOX_RTK_BASE) || (type == GPS_TYPE_UAVCAN_RTK_BASE)) &&
((get_type(instance^1) == GPS_TYPE_UBLOX_RTK_ROVER) || (get_type(instance^1) == GPS_TYPE_UAVCAN_RTK_ROVER))) {
// return the yaw from the rover