Ardupilot2/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Maxell.h
Randy Mackay dcc4f69f7c AP_BattMonitor: confirm pec support before attempting to read voltage
Previously we checked PEC support continuously at 10hz.  With this change PEC support (or lack of support) is determined first before we try to read from the battery.  Once determined, we do not repeat the checks.
Also simplified logic to determine PEC support based on version (should have no functional effect)
Also renamed get_pec_support to check_pec_support
Also renamed _pec_confirm to _pec_confirmed
2017-03-30 10:34:45 +09:00

44 lines
1.5 KiB
C++
Executable File

#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor_SMBus.h"
#include <AP_HAL/I2CDevice.h>
class AP_BattMonitor_SMBus_Maxell : public AP_BattMonitor_SMBus
{
public:
// Constructor
AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon, uint8_t instance,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
// read does nothing, all done in timer
void read() override;
private:
void timer(void);
// read word from register
// returns true if read was successful, false if failed
bool read_word(uint8_t reg, uint16_t& data) const;
// check if PEC supported with the version value in SpecificationInfo() function
// returns true once PEC is confirmed as working or not working
bool check_pec_support();
// read_block - returns number of characters read if successful, zero if unsuccessful
uint8_t read_block(uint8_t reg, uint8_t* data, bool append_zero) const;
// get_PEC - calculate PEC for a read or write from the battery
// buff is the data that was read or will be written
uint8_t get_PEC(const uint8_t i2c_addr, uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const;
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
uint8_t _pec_confirmed; // count of the number of times PEC has been confirmed as working
bool _pec_supported; // true if pec is supported
};