AP_UAVCAN: 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 0b95272f27
commit 55f21f367b
3 changed files with 5 additions and 27 deletions

View File

@ -357,9 +357,6 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters)
}
_led_conf.devices_count = 0;
if (enable_filters) {
configureCanAcceptanceFilters(*_node);
}
/*
* Informing other nodes that we're ready to work.

View File

@ -93,27 +93,6 @@ int16_t CanIface::receive(CanFrame& out_frame, MonotonicTime& out_ts_monotonic,
return ret;
}
/**
* Configure the hardware CAN filters. @ref CanFilterConfig.
*
* @return 0 = success, negative for error.
*/
int16_t CanIface::configureFilters(const CanFilterConfig* filter_configs, uint16_t num_configs)
{
if (can_iface_ == UAVCAN_NULLPTR) {
return -1;
}
AP_HAL::CANIface::CanFilterConfig* hal_filter_configs = new AP_HAL::CANIface::CanFilterConfig[num_configs];
if (hal_filter_configs == nullptr) {
return -1;
}
for (uint16_t i = 0; i < num_configs; i++) {
hal_filter_configs[i].id = filter_configs[i].id;
hal_filter_configs[i].mask = filter_configs[i].mask;
}
return can_iface_->configureFilters(hal_filter_configs, num_configs);
}
/**
* Number of available hardware filters.
*/

View File

@ -39,8 +39,10 @@ public:
virtual int16_t receive(CanFrame& out_frame, MonotonicTime& out_ts_monotonic,
UtcTime& out_ts_utc, CanIOFlags& out_flags) override;
int16_t configureFilters(const CanFilterConfig* filter_configs,
uint16_t num_configs) override;
virtual int16_t configureFilters(const CanFilterConfig* filter_configs,
uint16_t num_configs) override {
return 0;
}
uint16_t getNumFilters() const override;