AP_BattMonitor: make virtual Backend.init() optional to fix CANDriver.init(uint8, uint8) ambiguitiy

This commit is contained in:
Tom Pittenger 2021-04-22 13:04:45 -07:00 committed by Tom Pittenger
parent a365e18420
commit a7f81c838f
2 changed files with 1 additions and 4 deletions

View File

@ -29,7 +29,7 @@ public:
virtual ~AP_BattMonitor_Backend(void) {}
// initialise
virtual void init() = 0;
virtual void init() {};
// read the latest battery voltage
virtual void read() = 0;

View File

@ -29,9 +29,6 @@ public:
/// returns true if battery monitor provides current info
bool has_current() const override { return true; }
void init(void) override {}
protected:
// handler for incoming frames
void handle_frame(AP_HAL::CANFrame &frame) override;