AP_HAL_SITL: configure filter only if in FilteredMode

This commit is contained in:
bugobliterator 2020-09-27 02:31:08 +05:30 committed by Peter Barker
parent ba576247f0
commit 5f0c553982
1 changed files with 3 additions and 2 deletions

View File

@ -213,7 +213,7 @@ void CANIface::_poll(bool read, bool write)
bool CANIface::configureFilters(const CanFilterConfig* const filter_configs,
const std::uint16_t num_configs)
{
if (filter_configs == nullptr) {
if (filter_configs == nullptr || mode_ != FilteredMode) {
return false;
}
_hw_filters_container.clear();
@ -443,7 +443,8 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode)
{
char iface_name[16];
sprintf(iface_name, "vcan%u", _self_index);
bitrate_ = bitrate;
mode_ = mode;
if (_initialized) {
return _initialized;
}