diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index a50bcdc460..26a3538efa 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -183,7 +183,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Param: _AUTO_CONFIG // @DisplayName: Automatic GPS configuration // @Description: Controls if the autopilot should automatically configure the GPS based on the parameters and default settings - // @Values: 0:Disables automatic configuration,1:Enable automatic configuration,2:Enable automatic configuration for UAVCAN as well + // @Values: 0:Disables automatic configuration,1:Enable automatic configuration for Serial GPSes only,2:Enable automatic configuration for UAVCAN as well // @User: Advanced AP_GROUPINFO("_AUTO_CONFIG", 13, AP_GPS, _auto_config, 1), @@ -300,7 +300,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Param: _DRV_OPTIONS // @DisplayName: driver options // @Description: Additional backend specific options - // @Bitmask: 0:Use UART2/2nd CAN for moving baseline on ublox/uavcan,,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200 + // @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200,3:Use dedicated CAN port b/w GPSes for moving baseline // @User: Advanced AP_GROUPINFO("_DRV_OPTIONS", 22, AP_GPS, _driver_options, 0), #endif diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp index 44774f0c95..e7c4fcdd95 100644 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp @@ -894,14 +894,14 @@ bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_UAVCAN* ap_uavcan, uint } if (strcmp(name, "GPS_MB_ONLY_PORT") == 0 && cfg_step == STEP_SET_MB_CAN_TX) { - if (gps._driver_options == 0 && value != 1) { + if ((gps._driver_options & UAVCAN_MBUseDedicatedBus) && !value) { // set up so that another CAN port is used for the Moving Baseline Data // setting this value will allow another CAN port to be used as dedicated // line for the Moving Baseline Data value = 1; requires_save_and_reboot = true; return true; - } else if (gps._driver_options != 0 && value != 0) { + } else if (!(gps._driver_options & UAVCAN_MBUseDedicatedBus) && value) { // set up so that all CAN ports are used for the Moving Baseline Data value = 0; requires_save_and_reboot = true; diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index a78bf38088..6510482ad8 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -88,6 +88,7 @@ public: UBX_MBUseUart2 = (1U << 0U), SBF_UseBaseForYaw = (1U << 1U), UBX_Use115200 = (1U << 2U), + UAVCAN_MBUseDedicatedBus = (1 << 3U), }; protected: