mirror of https://github.com/ArduPilot/ardupilot
Sub: move to using CANManager library
This commit is contained in:
parent
fb180fa431
commit
5318175f70
|
@ -490,10 +490,10 @@ const AP_Param::Info Sub::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
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
|
|
@ -66,7 +66,7 @@ public:
|
|||
k_param_serial_manager, // Serial ports, AP_SerialManager
|
||||
k_param_notify, // Notify Library, AP_Notify
|
||||
k_param_arming = 26, // Arming checks
|
||||
k_param_BoardConfig_CAN,
|
||||
k_param_can_mgr,
|
||||
|
||||
// Sensor objects
|
||||
k_param_ins = 30, // AP_InertialSensor
|
||||
|
|
|
@ -15,8 +15,8 @@ static void failsafe_check_static()
|
|||
void Sub::init_ardupilot()
|
||||
{
|
||||
BoardConfig.init();
|
||||
#if HAL_WITH_UAVCAN
|
||||
BoardConfig_CAN.init();
|
||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
can_mgr.init();
|
||||
#endif
|
||||
|
||||
#if AP_FEATURE_BOARD_DETECT
|
||||
|
|
Loading…
Reference in New Issue