AP_HAL_ChibiOS: 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:
parent
b6bf74b73d
commit
33ebc83a68
@ -399,8 +399,9 @@ int16_t CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& out_timestamp_u
|
||||
bool CANIface::configureFilters(const CanFilterConfig* filter_configs,
|
||||
uint16_t num_configs)
|
||||
{
|
||||
#if defined(STM32G4)
|
||||
// not supported yet
|
||||
// only enable filters in AP_Periph. It makes no sense on the flight controller
|
||||
#if !defined(HAL_BUILD_AP_PERIPH) || defined(STM32G4)
|
||||
// no filtering
|
||||
can_->CCCR &= ~FDCAN_CCCR_INIT; // Leave init mode
|
||||
uint32_t while_start_ms = AP_HAL::millis();
|
||||
while ((can_->CCCR & FDCAN_CCCR_INIT) == 1) {
|
||||
@ -525,7 +526,7 @@ bool CANIface::configureFilters(const CanFilterConfig* filter_configs,
|
||||
}
|
||||
initialised_ = true;
|
||||
return true;
|
||||
#endif // defined(STM32G4)
|
||||
#endif // AP_Periph, STM32G4
|
||||
}
|
||||
|
||||
uint16_t CANIface::getNumFilters() const
|
||||
|
@ -384,6 +384,11 @@ int16_t CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& out_timestamp_u
|
||||
bool CANIface::configureFilters(const CanFilterConfig* filter_configs,
|
||||
uint16_t num_configs)
|
||||
{
|
||||
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||
// only do filtering for AP_Periph
|
||||
can_->FMR &= ~bxcan::FMR_FINIT;
|
||||
return true;
|
||||
#else
|
||||
if (mode_ != FilteredMode) {
|
||||
return false;
|
||||
}
|
||||
@ -451,6 +456,7 @@ bool CANIface::configureFilters(const CanFilterConfig* filter_configs,
|
||||
}
|
||||
|
||||
return false;
|
||||
#endif // AP_Periph
|
||||
}
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user