AP_CANManager: disable CAN filtering except on AP_Periph

this saves flash space and makes CAN forwarding for any bus without
reconfigure/reboot easy. CAN filtering is not useful in the main
flight controller firmware as we want to see nearly all packets
This commit is contained in:
Andrew Tridgell 2022-02-09 14:25:44 +11:00
parent 124c9d5d9b
commit b6bf74b73d
1 changed files with 3 additions and 1 deletions

View File

@ -167,9 +167,11 @@ void AP_CANManager::init()
// we have slcan bridge setup pass that on as can iface
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, AP_HAL::CANIface::NormalMode);
iface = &_slcan_interface;
#ifdef HAL_BUILD_AP_PERIPH
} else if(drv_type[drv_num] == Driver_Type_UAVCAN) {
// We do Message ID filtering when using UAVCAN without SLCAN
// setup for filtering on AP_Periph if using UAVCAN
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, AP_HAL::CANIface::FilteredMode);
#endif
} else {
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, AP_HAL::CANIface::NormalMode);
}