mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: fixed moving baseline yaw for single CAN peripherals
the AP_GPS_UAVCAN driver requires this param for auto-config of MB yaw on DroneCAN GPS
This commit is contained in:
parent
1858969697
commit
0853accea1
|
@ -173,7 +173,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||
// @RebootRequired: True
|
||||
GSCALAR(gps_port, "GPS_PORT", HAL_PERIPH_GPS_PORT_DEFAULT),
|
||||
|
||||
#if HAL_NUM_CAN_IFACES >= 2
|
||||
#if GPS_MOVING_BASELINE
|
||||
// @Param: MB_CAN_PORT
|
||||
// @DisplayName: Moving Baseline CAN Port option
|
||||
// @Description: Autoselect dedicated CAN port on which moving baseline data will be transmitted.
|
||||
|
|
|
@ -95,7 +95,7 @@ public:
|
|||
|
||||
#ifdef HAL_PERIPH_ENABLE_GPS
|
||||
AP_Int8 gps_port;
|
||||
#if HAL_NUM_CAN_IFACES >= 2
|
||||
#if GPS_MOVING_BASELINE
|
||||
AP_Int8 gps_mb_only_can_port;
|
||||
#endif
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue