mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: use separate register_driver method while contructing CAN Driver
This commit is contained in:
parent
1bac7283ab
commit
ae0d11a26d
|
@ -20,8 +20,10 @@ public:
|
|||
// construct the CAN Sensor
|
||||
AP_BattMonitor_MPPT_PacketDigital(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms):
|
||||
AP_BattMonitor_Backend(mon, mon_state, params),
|
||||
CANSensor("MPPT", AP_CANManager::Driver_Type_MPPT_PacketDigital)
|
||||
{ };
|
||||
CANSensor("MPPT")
|
||||
{
|
||||
register_driver(AP_CANManager::Driver_Type_MPPT_PacketDigital);
|
||||
}
|
||||
|
||||
/// Read the battery voltage and current. Should be called at 10hz
|
||||
void read() override;
|
||||
|
|
Loading…
Reference in New Issue