mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 06:28:32 -04:00
AP_BattMonitor: SMBus: Read serial number
This commit is contained in:
parent
302ea1204f
commit
3ab3face9b
@ -68,7 +68,11 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
|
||||
AP_GROUPINFO("_WATT_MAX", 9, AP_BattMonitor, _watt_max[0], AP_BATT_MAX_WATT_DEFAULT),
|
||||
#endif
|
||||
|
||||
// 10 is left for future expansion
|
||||
// @Param: _SERIAL_NUM
|
||||
// @DisplayName: Battery serial number
|
||||
// @Description: Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_SERIAL_NUM", 10, AP_BattMonitor, _serial_numbers[0], AP_BATT_SERIAL_NUMBER_DEFAULT),
|
||||
|
||||
#if AP_BATT_MONITOR_MAX_INSTANCES > 1
|
||||
// @Param: 2_MONITOR
|
||||
@ -131,6 +135,12 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
|
||||
AP_GROUPINFO("2_WATT_MAX", 18, AP_BattMonitor, _watt_max[1], AP_BATT_MAX_WATT_DEFAULT),
|
||||
#endif
|
||||
|
||||
// @Param: 2_SERIAL_NUM
|
||||
// @DisplayName: Battery serial number
|
||||
// @Description: Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2_SERIAL_NUM", 20, AP_BattMonitor, _serial_numbers[1], AP_BATT_SERIAL_NUMBER_DEFAULT),
|
||||
|
||||
#endif // AP_BATT_MONITOR_MAX_INSTANCES > 1
|
||||
|
||||
AP_GROUPEND
|
||||
|
@ -14,6 +14,7 @@
|
||||
#define AP_BATT_CAPACITY_DEFAULT 3300
|
||||
#define AP_BATT_LOW_VOLT_TIMEOUT_MS 10000 // low voltage of 10 seconds will cause battery_exhausted to return true
|
||||
#define AP_BATT_MAX_WATT_DEFAULT 0
|
||||
#define AP_BATT_SERIAL_NUMBER_DEFAULT -1
|
||||
|
||||
#define AP_BATT_MONITOR_TIMEOUT 5000
|
||||
|
||||
@ -147,6 +148,7 @@ protected:
|
||||
AP_Float _curr_amp_offset[AP_BATT_MONITOR_MAX_INSTANCES]; /// offset voltage that is subtracted from current pin before conversion to amps
|
||||
AP_Int32 _pack_capacity[AP_BATT_MONITOR_MAX_INSTANCES]; /// battery pack capacity less reserve in mAh
|
||||
AP_Int16 _watt_max[AP_BATT_MONITOR_MAX_INSTANCES]; /// max battery power allowed. Reduce max throttle to reduce current to satisfy this limit
|
||||
AP_Int32 _serial_numbers[AP_BATT_MONITOR_MAX_INSTANCES]; /// battery serial number, automatically filled in on SMBus batteries
|
||||
|
||||
private:
|
||||
BattMonitor_State state[AP_BATT_MONITOR_MAX_INSTANCES];
|
||||
|
@ -3,6 +3,26 @@
|
||||
#define AP_BATTMONITOR_SMBUS_PEC_POLYNOME 0x07 // Polynome for CRC generation
|
||||
|
||||
#define BATTMONITOR_SMBUS_TEMP 0x08 // temperature register
|
||||
#define BATTMONITOR_SMBUS_SERIAL 0x1C // serial number
|
||||
AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon,
|
||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
: AP_BattMonitor_Backend(mon, mon_state),
|
||||
_dev(std::move(dev))
|
||||
{
|
||||
_mon._serial_numbers[_state.instance] = AP_BATT_SERIAL_NUMBER_DEFAULT;
|
||||
}
|
||||
|
||||
/// read the battery_voltage and current, should be called at 10hz
|
||||
void AP_BattMonitor_SMBus::read(void)
|
||||
{
|
||||
// nothing to be done here for actually interacting with the battery
|
||||
// however we can use this to set any parameters that need to be set
|
||||
|
||||
if (_serial_number != _mon._serial_numbers[_state.instance]) {
|
||||
_mon._serial_numbers[_state.instance].set_and_notify(_serial_number);
|
||||
}
|
||||
}
|
||||
|
||||
// reads the temperature word from the battery
|
||||
// returns true if the read was successful
|
||||
@ -18,6 +38,22 @@ bool AP_BattMonitor_SMBus::read_temp(void)
|
||||
return false;
|
||||
}
|
||||
|
||||
// reads the serial number if it's not already known
|
||||
// returns true if the read was successful or the number was already known
|
||||
bool AP_BattMonitor_SMBus::read_serial_number(void) {
|
||||
uint16_t data;
|
||||
|
||||
// don't recheck the serial number if we already have it
|
||||
if (_serial_number != -1) {
|
||||
return true;
|
||||
} else if (read_word(BATTMONITOR_SMBUS_SERIAL, data)) {
|
||||
_serial_number = data;
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
// read word from register
|
||||
// returns true if read was successful, false if failed
|
||||
bool AP_BattMonitor_SMBus::read_word(uint8_t reg, uint16_t& data) const
|
||||
|
@ -18,10 +18,7 @@ public:
|
||||
/// Constructor
|
||||
AP_BattMonitor_SMBus(AP_BattMonitor &mon, uint8_t instance,
|
||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
: AP_BattMonitor_Backend(mon, instance, mon_state),
|
||||
_dev(std::move(dev))
|
||||
{}
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
|
||||
// virtual destructor to reduce compiler warnings
|
||||
virtual ~AP_BattMonitor_SMBus() {}
|
||||
@ -29,10 +26,16 @@ public:
|
||||
|
||||
protected:
|
||||
|
||||
void read(void) override;
|
||||
|
||||
// reads the temperature word from the battery
|
||||
// returns true if the read was successful
|
||||
bool read_temp(void);
|
||||
|
||||
// reads the serial number if it's not already known
|
||||
// returns true if the read was successful, or the number was already known
|
||||
bool read_serial_number(void);
|
||||
|
||||
// read word from register
|
||||
// returns true if read was successful, false if failed
|
||||
bool read_word(uint8_t reg, uint16_t& data) const;
|
||||
@ -44,6 +47,8 @@ protected:
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
|
||||
bool _pec_supported; // true if PEC is supported
|
||||
|
||||
int32_t _serial_number = -1; // battery serial number
|
||||
|
||||
};
|
||||
|
||||
// include specific implementations
|
||||
|
@ -44,12 +44,6 @@ AP_BattMonitor_SMBus_Maxell::AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon, ui
|
||||
_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus_Maxell::timer, void));
|
||||
}
|
||||
|
||||
/// Read the battery voltage and current. Should be called at 10hz
|
||||
void AP_BattMonitor_SMBus_Maxell::read()
|
||||
{
|
||||
// nothing to do - all done in timer()
|
||||
}
|
||||
|
||||
void AP_BattMonitor_SMBus_Maxell::timer()
|
||||
{
|
||||
// check if PEC is supported
|
||||
@ -89,6 +83,8 @@ void AP_BattMonitor_SMBus_Maxell::timer()
|
||||
}
|
||||
|
||||
read_temp();
|
||||
|
||||
read_serial_number();
|
||||
}
|
||||
|
||||
// read_block - returns number of characters read if successful, zero if unsuccessful
|
||||
|
@ -15,9 +15,6 @@ public:
|
||||
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);
|
||||
|
@ -38,12 +38,6 @@ AP_BattMonitor_SMBus_Solo::AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon, uint8_
|
||||
_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus_Solo::timer, void));
|
||||
}
|
||||
|
||||
/// Read the battery voltage and current. Should be called at 10hz
|
||||
void AP_BattMonitor_SMBus_Solo::read()
|
||||
{
|
||||
// nothing to do - all done in timer()
|
||||
}
|
||||
|
||||
void AP_BattMonitor_SMBus_Solo::timer()
|
||||
{
|
||||
uint16_t data;
|
||||
@ -118,6 +112,8 @@ void AP_BattMonitor_SMBus_Solo::timer()
|
||||
}
|
||||
|
||||
read_temp();
|
||||
|
||||
read_serial_number();
|
||||
}
|
||||
|
||||
// read_block - returns number of characters read if successful, zero if unsuccessful
|
||||
|
@ -15,9 +15,6 @@ public:
|
||||
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);
|
||||
|
Loading…
Reference in New Issue
Block a user