Browse Source

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

zr-v5.1
bugobliterator 4 years ago committed by Peter Barker
parent
commit
d1eb9e8aea
  1. 8
      libraries/AP_HAL/CANIface.h

8
libraries/AP_HAL/CANIface.h

@ -94,9 +94,12 @@ public: @@ -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: @@ -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_;
};

Loading…
Cancel
Save