diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 63da701d37..bca2720774 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -320,10 +320,10 @@ const AP_Param::Info Rover::var_info[] = { // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp GOBJECT(BoardConfig, "BRD_", AP_BoardConfig), -#if HAL_WITH_UAVCAN +#if HAL_MAX_CAN_PROTOCOL_DRIVERS // @Group: CAN_ - // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp - GOBJECT(BoardConfig_CAN, "CAN_", AP_BoardConfig_CAN), + // @Path: ../libraries/AP_CANManager/AP_CANManager.cpp + GOBJECT(can_mgr, "CAN_", AP_CANManager), #endif // GPS driver diff --git a/Rover/Parameters.h b/Rover/Parameters.h index 0d7e838c77..6039134401 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -26,7 +26,7 @@ public: // k_param_format_version = 0, k_param_software_type, // unused - k_param_BoardConfig_CAN, + k_param_can_mgr, // Misc // diff --git a/Rover/system.cpp b/Rover/system.cpp index d29969e05c..fbdeabc12f 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -20,8 +20,8 @@ void Rover::init_ardupilot() #endif BoardConfig.init(); -#if HAL_WITH_UAVCAN - BoardConfig_CAN.init(); +#if HAL_MAX_CAN_PROTOCOL_DRIVERS + can_mgr.init(); #endif // init gripper