aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorRandy Mackay <rmackay9@yahoo.com>2015-04-08 22:33:07 -0700
committerRandy Mackay <rmackay9@yahoo.com>2015-04-10 14:17:25 +0900
commit04863dc2d1975433d95f7922886e335ddca5fabc (patch)
tree0e99d03e4317ade3e50f9f82c729355623aa2ebc
parent79f645974088aaf73b1d76266cac55346295f5b6 (diff)
downloadpx4-firmware-04863dc2d1975433d95f7922886e335ddca5fabc.tar.gz
px4-firmware-04863dc2d1975433d95f7922886e335ddca5fabc.tar.bz2
px4-firmware-04863dc2d1975433d95f7922886e335ddca5fabc.zip
batt_smbus: add ioctl to return batt capacity
Also use full charge capacity instead of design capacity so that an old battery's capacity will appear as lower than its original capacity but it will still report 100% charged after charging
-rw-r--r--src/drivers/batt_smbus/batt_smbus.cpp53
-rw-r--r--src/drivers/drv_batt_smbus.h10
2 files changed, 53 insertions, 10 deletions
diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp
index 9f72bd56f..6d1b3f6ca 100644
--- a/src/drivers/batt_smbus/batt_smbus.cpp
+++ b/src/drivers/batt_smbus/batt_smbus.cpp
@@ -85,6 +85,7 @@
#define BATT_SMBUS_TEMP 0x08 ///< temperature register
#define BATT_SMBUS_VOLTAGE 0x09 ///< voltage register
#define BATT_SMBUS_REMAINING_CAPACITY 0x0f ///< predicted remaining battery capacity as a percentage
+#define BATT_SMBUS_FULL_CHARGE_CAPACITY 0x10 ///< capacity when fully charged
#define BATT_SMBUS_DESIGN_CAPACITY 0x18 ///< design capacity register
#define BATT_SMBUS_DESIGN_VOLTAGE 0x19 ///< design voltage register
#define BATT_SMBUS_SERIALNUM 0x1c ///< serial number register
@@ -116,6 +117,11 @@ public:
virtual int init();
/**
+ * ioctl for retrieving battery capacity and time to empty
+ */
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
* Test device
*
* @return 0 on success, error code on failure
@@ -180,7 +186,7 @@ private:
orb_advert_t _batt_topic; ///< uORB battery topic
orb_id_t _batt_orb_id; ///< uORB battery topic ID
uint64_t _start_time; ///< system time we first attempt to communicate with battery
- uint16_t _batt_design_capacity; ///< battery's design capacity in mAh (0 means unknown)
+ uint16_t _batt_capacity; ///< battery's design capacity in mAh (0 means unknown)
};
namespace
@@ -200,7 +206,7 @@ BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) :
_batt_topic(-1),
_batt_orb_id(nullptr),
_start_time(0),
- _batt_design_capacity(0)
+ _batt_capacity(0)
{
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
@@ -251,6 +257,31 @@ BATT_SMBUS::init()
}
int
+BATT_SMBUS::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int ret = -ENODEV;
+
+ switch (cmd) {
+ case BATT_SMBUS_GET_CAPACITY:
+
+ /* return battery capacity as uint16 */
+ if (_enabled) {
+ *((uint16_t *)arg) = _batt_capacity;
+ ret = OK;
+ }
+
+ break;
+
+ default:
+ /* see if the parent class can make any use of it */
+ ret = CDev::ioctl(filp, cmd, arg);
+ break;
+ }
+
+ return ret;
+}
+
+int
BATT_SMBUS::test()
{
int sub = orb_subscribe(ORB_ID(battery_status));
@@ -266,7 +297,8 @@ BATT_SMBUS::test()
if (updated) {
if (orb_copy(ORB_ID(battery_status), sub, &status) == OK) {
- warnx("V=%4.2f C=%4.2f DismAh=%4.2f", (float)status.voltage_v, (float)status.current_a, (float)status.discharged_mah);
+ warnx("V=%4.2f C=%4.2f DismAh=%4.2f Cap:%d", (float)status.voltage_v, (float)status.current_a,
+ (float)status.discharged_mah, (int)_batt_capacity);
}
}
@@ -374,21 +406,22 @@ BATT_SMBUS::cycle()
uint8_t buff[4];
if (read_block(BATT_SMBUS_CURRENT, buff, 4, false) == 4) {
- new_report.current_a = -(float)((int32_t)((uint32_t)buff[3] << 24 | (uint32_t)buff[2] << 16 | (uint32_t)buff[1] << 8 | (uint32_t)buff[0])) / 1000.0f;
+ new_report.current_a = -(float)((int32_t)((uint32_t)buff[3] << 24 | (uint32_t)buff[2] << 16 | (uint32_t)buff[1] << 8 |
+ (uint32_t)buff[0])) / 1000.0f;
}
// read battery design capacity
- if (_batt_design_capacity == 0) {
- if (read_reg(BATT_SMBUS_DESIGN_CAPACITY, tmp) == OK) {
- _batt_design_capacity = tmp;
+ if (_batt_capacity == 0) {
+ if (read_reg(BATT_SMBUS_FULL_CHARGE_CAPACITY, tmp) == OK) {
+ _batt_capacity = tmp;
}
}
// read remaining capacity
- if (_batt_design_capacity > 0) {
+ if (_batt_capacity > 0) {
if (read_reg(BATT_SMBUS_REMAINING_CAPACITY, tmp) == OK) {
- if (tmp < _batt_design_capacity) {
- new_report.discharged_mah = _batt_design_capacity - tmp;
+ if (tmp < _batt_capacity) {
+ new_report.discharged_mah = _batt_capacity - tmp;
}
}
}
diff --git a/src/drivers/drv_batt_smbus.h b/src/drivers/drv_batt_smbus.h
index f12e2bfb3..57af0a0b6 100644
--- a/src/drivers/drv_batt_smbus.h
+++ b/src/drivers/drv_batt_smbus.h
@@ -45,3 +45,13 @@
/* device path */
#define BATT_SMBUS0_DEVICE_PATH "/dev/batt_smbus0"
+
+/*
+ * ioctl() definitions
+ */
+
+#define _BATT_SMBUS_IOCBASE (0x2e00)
+#define _BATT_SMBUS_IOC(_n) (_IOC(_BATT_SMBUS_IOCBASE, _n))
+
+/** retrieve battery capacity */
+#define BATT_SMBUS_GET_CAPACITY _BATT_SMBUS_IOC(1)