mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_HAL: add FilteredCAN mode to tell driver to init as such
This commit is contained in:
parent
46827f0c91
commit
d1eb9e8aea
@ -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_;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user