mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_BattMonitor: make virtual Backend.init() optional to fix CANDriver.init(uint8, uint8) ambiguitiy
This commit is contained in:
parent
a365e18420
commit
a7f81c838f
@ -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;
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user