AP_HAL: add FilteredCAN mode to tell driver to init as such

This commit is contained in:
bugobliterator 2020-09-27 01:39:01 +05:30 committed by Peter Barker
parent 46827f0c91
commit d1eb9e8aea

View File

@ -94,9 +94,12 @@ public:
enum OperatingMode {
PassThroughMode,
NormalMode,
SilentMode
SilentMode,
FilteredMode
};
OperatingMode get_operating_mode() { return mode_; }
typedef uint16_t CanIOFlags;
static const CanIOFlags Loopback = 1;
static const CanIOFlags AbortOnError = 2;
@ -206,4 +209,7 @@ public:
// return true if init was called and successful
virtual bool is_initialized() const = 0;
protected:
uint32_t bitrate_;
OperatingMode mode_;
};