summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-22 18:03:13 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-22 18:03:13 +0000
commita059004e062322e56a9d5809099c212d40ab4292 (patch)
tree41752cf13c5bf7facdb0d28106cd31f76ad6d7e1 /nuttx/drivers
parent3d2ac1dd78fbec255823415ef5498d35056b7361 (diff)
downloadpx4-nuttx-a059004e062322e56a9d5809099c212d40ab4292.tar.gz
px4-nuttx-a059004e062322e56a9d5809099c212d40ab4292.tar.bz2
px4-nuttx-a059004e062322e56a9d5809099c212d40ab4292.zip
Create a generic battery driver infrastructure
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4322 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/power/Make.defs43
-rw-r--r--nuttx/drivers/power/battery.c255
-rw-r--r--nuttx/drivers/power/max1704x.c149
3 files changed, 363 insertions, 84 deletions
diff --git a/nuttx/drivers/power/Make.defs b/nuttx/drivers/power/Make.defs
index 91102c1e9..261e7525c 100644
--- a/nuttx/drivers/power/Make.defs
+++ b/nuttx/drivers/power/Make.defs
@@ -33,26 +33,53 @@
#
############################################################################
-# Has power management support been initialized?
-
-ifeq ($(CONFIG_PM),y)
+POWER_DEPPATH =
+POWER_VPATH =
+POWER_CFLAGS =
# Include power management sources
+ifeq ($(CONFIG_PM),y)
+
CSRCS += pm_activity.c pm_changestate.c pm_checkstate.c pm_initialize.c pm_register.c pm_update.c
-# Add I2C devices
+# Include power management in the build
+
+POWER_DEPPATH := --dep-path power
+POWER_VPATH := :power
+POWER_CFLAGS := ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power}
+
+endif
+
+# Add battery drivers
+
+ifeq ($(CONFIG_BATTERY),y)
+
+CSRCS += battery.c
+
+# Add I2C-based battery drivers
ifeq ($(CONFIG_I2C),y)
+
+# Add the MAX1704x I2C-based battery driver
+
ifeq ($(CONFIG_I2C_MAX1704X),y)
CSRCS += max1704x.c
endif
+
+endif
+
+# Include battery suport in the build
+
+POWER_DEPPATH := --dep-path power
+POWER_VPATH := :power
+POWER_CFLAGS := ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power}
+
endif
# Include power management in the build
-DEPPATH += --dep-path power
-VPATH += :power
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/power}
-endif
+DEPPATH += $(POWER_DEPPATH)
+VPATH += $(POWER_VPATH)
+CFLAGS += $(POWER_CFLAGS);
diff --git a/nuttx/drivers/power/battery.c b/nuttx/drivers/power/battery.c
new file mode 100644
index 000000000..e4f8c1dd3
--- /dev/null
+++ b/nuttx/drivers/power/battery.c
@@ -0,0 +1,255 @@
+/****************************************************************************
+ * drivers/power/battery.c
+ * Upper-half, character driver for batteries.
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/power/battery.h>
+
+/* This driver requires:
+ *
+ * CONFIG_BATTERY - Upper half battery driver support
+ */
+
+#if defined(CONFIG_BATTERY)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private
+ ****************************************************************************/
+
+struct bat_dev_s
+{
+ FAR struct battery_lower_s *lower; /* The lower half battery driver */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* Character driver methods */
+
+static int bat_open(FAR struct file *filep);
+static int bat_close(FAR struct file *filep);
+static ssize_t bat_read(FAR struct file *, FAR char *, size_t);
+static ssize_t bat_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
+static int bat_ioctl(FAR struct file *filep,int cmd,unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct battery_operations_s g_max1704xfopg =
+{
+ bat_open,
+ bat_close,
+ bat_read,
+ bat_write,
+ 0,
+ bat_ioctl
+#ifndef CONFIG_DISABLE_POLL
+ , 0
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: bat_open
+ *
+ * Description:
+ * This function is called whenever theMAX1704x device is opened.
+ *
+ ****************************************************************************/
+
+static int bat_open(FAR struct file *filep)
+{
+ return OK;
+}
+
+/****************************************************************************
+ * Name: bat_close
+ *
+ * Description:
+ * This routine is called when theMAX1704x device is closed.
+ *
+ ****************************************************************************/
+
+static int bat_close(FAR struct file *filep)
+{
+ return OK;
+}
+
+/****************************************************************************
+ * Name: bat_read
+ ****************************************************************************/
+
+static ssize_t bat_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
+{
+ return 0;
+}
+
+/****************************************************************************
+ * Name: bat_write
+ ****************************************************************************/
+
+static ssize_t bat_write(FAR struct file *filep, FAR const char *buffer,
+ size_t buflen)
+{
+ return -EACCESS;
+}
+
+/****************************************************************************
+ * Name: bat_ioctl
+ ****************************************************************************/
+
+static int bat_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+{
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct bat_dev_s *upper = inode->i_private;
+ int ret = -EINVAL;
+
+ switch (cmd)
+ {
+ case BATIOC_STATE:
+ {
+ FAR int *ptr = (FAR int *)((uintptr_t)arg));
+ if (ptr)
+ {
+ *ptr = upper->state(priv->lower);
+ ret = OK;
+ }
+ }
+ break;
+
+ case BATIOC_ONLINE:
+ FAR bool *ptr = (FAR bool *)((uintptr_t)arg));
+ if (ptr)
+ {
+ *ptr = upper->online(priv->lower);
+ ret = OK;
+ }
+ break;
+
+ case BATIOC_VOLTAGE:
+ {
+ FAR int *ptr = (FAR int *)((uintptr_t)arg));
+ if (ptr)
+ {
+ *ptr = upper->voltage(priv->lower);
+ ret = OK;
+ }
+ }
+ break;
+
+ case BATIOC_CAPACITY:
+ {
+ FAR int *ptr = (FAR int *)((uintptr_t)arg));
+ if (ptr)
+ {
+ *ptr = upper->capacity(priv->lower);
+ ret = OK;
+ }
+ }
+ break;
+
+ default:
+ i2cdbg("Unrecognized cmd: %d\n", cmd);
+ ret = -ENOTTY;
+ break;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: battery_register
+ *
+ * Description:
+ * Register a lower half battery driver with the common, upper-half
+ * battery driver.
+ *
+ * Input parameters:
+ * devpath - The location in the pseudo-filesystem to create the driver.
+ * Recommended standard is "/dev/bat0", "/dev/bat1", etc.
+ * lower - The lower half battery state.
+ *
+ * Returned value:
+ * Zero on success or a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int battery_register(FAR const char *devpath, FAR struct battery_lower_s *lower)
+{
+ FAR struct bat_dev_s *upper;
+ int ret;
+
+ /* Initialize theMAX1704x device structure */
+
+ upper = (FAR struct bat_dev_s *)kzalloc(sizeof(struct bat_dev_s));
+ if (!upper)
+ {
+ i2cdbg("Failed to allocate instance\n");
+ return -ENOMEM;
+ }
+
+ upper->lower = lower;
+
+ /* Register the character driver */
+
+ ret = register_driver(devpath, &g_max1704xfopg, 0555, upper);
+ if (ret < 0)
+ {
+ i2cdbg("Failed to register driver: %d\n", ret);
+ free(upper);
+ }
+ return ret;
+}
+#endif /* CONFIG_BATTERY */
diff --git a/nuttx/drivers/power/max1704x.c b/nuttx/drivers/power/max1704x.c
index bba53478a..06184a562 100644
--- a/nuttx/drivers/power/max1704x.c
+++ b/nuttx/drivers/power/max1704x.c
@@ -1,6 +1,6 @@
/****************************************************************************
* drivers/power/max1704x.c
- * Character driver for the STMicroMAX1704x Temperature Sensor
+ * Lower half driver for MAX1704x battery charger
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -43,7 +43,16 @@
#include <errno.h>
#include <debug.h>
-#if defined(CONFIG_I2C) && defined(CONFIG_I2C_MAX1704X)
+#include <nuttx/power/battery.h>
+
+/* This driver requires:
+ *
+ * CONFIG_BATTERY - Upper half battery driver support
+ * CONFIG_I2C - I2C support
+ * CONFIG_I2C_MAX1704X - And the driver must be explictly selected.
+ */
+
+#if defined(CONFIG_BATTERY) && defined(CONFIG_I2C) && defined(CONFIG_I2C_MAX1704X)
/****************************************************************************
* Pre-processor Definitions
@@ -55,6 +64,12 @@
struct max1704x_dev_s
{
+ /* The common part of the battery driver visible to the upper-half driver */
+
+ FAR const struct battery_operations_s *ops; /* Battery operations */
+
+ /* Data fields specific to the lower half MAX1704x driver follow */
+
FAR struct i2c_dev_s *i2c; /* I2C interface */
uint8_t addr; /* I2C address */
};
@@ -62,100 +77,84 @@ struct max1704x_dev_s
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
-/* I2C Helpers */
-/* Character driver methods */
+/* Battery driver lower half methods */
-static int max1704x_open(FAR struct file *filep);
-static int max1704x_close(FAR struct file *filep);
-static ssize_t max1704x_read(FAR struct file *, FAR char *, size_t);
-static ssize_t max1704x_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
-static int max1704x_ioctl(FAR struct file *filep,int cmd,unsigned long arg);
+static enum battery_status_e mx1704x_state(struct battery_lower_s *lower);
+static bool mx1704x_online(struct battery_lower_s *lower);
+static int mx1704x_voltage(struct battery_lower_s *lower);
+static int mx1704x_capacity(struct battery_lower_s *lower);
/****************************************************************************
* Private Data
****************************************************************************/
-static const struct file_operations g_max1704xfopg =
+static const struct battery_operations_s g_max1704xfopg =
{
- max1704x_open,
- max1704x_close,
- max1704x_read,
- max1704x_write,
- 0,
- max1704x_ioctl
-#ifndef CONFIG_DISABLE_POLL
- , 0
-#endif
+ mx1704x_state,
+ mx1704x_online,
+ mx1704x_voltage,
+ mx1704x_capacity,
};
/****************************************************************************
* Private Functions
****************************************************************************/
+
/****************************************************************************
* Name: max1704x_open
*
* Description:
- * This function is called whenever theMAX1704x device is opened.
+ * Return the current battery state
*
****************************************************************************/
-static int max1704x_open(FAR struct file *filep)
+static enum battery_status_e state(struct battery_lower_s *lower)
{
- return OK;
+#warning "Missing logic"
+ return BATTERY_UNKNOWN;
}
/****************************************************************************
- * Name: max1704x_close
+ * Name: max1704x_open
*
* Description:
- * This routine is called when theMAX1704x device is closed.
+ * Return true if the batter is online
*
****************************************************************************/
-static int max1704x_close(FAR struct file *filep)
+static bool online(struct battery_lower_s *lower)
{
- return OK;
+#warning "Missing logic"
+ return false;
}
/****************************************************************************
- * Name: max1704x_read
- ****************************************************************************/
-
-static ssize_t max1704x_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
-{
- retrun 0;
-}
-
-/****************************************************************************
- * Name: max1704x_write
+ * Name: max1704x_open
+ *
+ * Description:
+ * Current battery voltage
+ *
****************************************************************************/
-static ssize_t max1704x_write(FAR struct file *filep, FAR const char *buffer,
- size_t buflen)
+static int voltage(struct battery_lower_s *lower);
{
- return -EACCESS;
+#warning "Missing logic"
+ return 0;
}
/****************************************************************************
- * Name: max1704x_ioctl
+ * Name: max1704x_open
+ *
+ * Description:
+ * Battery capacity
+ *
****************************************************************************/
-static int max1704x_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+static int capacity(struct battery_lower_s *lower);
{
- FAR struct inode *inode = filep->f_inode;
- FAR struct max1704x_dev_s *priv = inode->i_private;
- int ret = OK;
-
- switch (cmd)
- {
- default:
- i2cdbg("Unrecognized cmd: %d\n", cmd);
- ret = -ENOTTY;
- break;
- }
-
- return ret;
+#warning "Missing logic"
+ return 0;
}
/****************************************************************************
@@ -163,22 +162,30 @@ static int max1704x_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
****************************************************************************/
/****************************************************************************
- * Name: max1704x_register
+ * Name: max1704x_initialize
*
* Description:
- * Register theMAX1704x character device as 'devpath'
+ * Initialize the MAX1704x battery driver and return an instance of the
+ * lower_half interface that may be used with battery_register();
+ *
+ * This driver requires:
+ *
+ * CONFIG_BATTERY - Upper half battery driver support
+ * CONFIG_I2C - I2C support
+ * CONFIG_I2C_MAX1704X - And the driver must be explictly selected.
*
* Input Parameters:
- * devpath - The full path to the driver to register. E.g., "/dev/temp0"
* i2c - An instance of the I2C interface to use to communicate with the MAX1704x
* addr - The I2C address of the MAX1704x.
*
* Returned Value:
- * Zero (OK) on success; a negated errno value on failure.
+ * A pointer to the intialized lower-half driver instance. A NULL pointer
+ * is returned on a failure to initialize the MAX1704x lower half.
*
****************************************************************************/
-int max1704x_register(FAR const char *devpath, FAR struct i2c_dev_s *i2c, uint8_t addr)
+FAR struct battery_lower_s *max1704x_initialize(FAR struct i2c_dev_s *i2c,
+ uint8_t addr)
{
FAR struct max1704x_dev_s *priv;
int ret;
@@ -186,23 +193,13 @@ int max1704x_register(FAR const char *devpath, FAR struct i2c_dev_s *i2c, uint8_
/* Initialize theMAX1704x device structure */
priv = (FAR struct max1704x_dev_s *)kzalloc(sizeof(struct max1704x_dev_s));
- if (!priv)
- {
- i2cdbg("Failed to allocate instance\n");
- return -ENOMEM;
- }
-
- priv->i2c = i2c;
- priv->addr = addr;
-
- /* Register the character driver */
-
- ret = register_driver(devpath, &g_max1704xfopg, 0555, priv);
- if (ret < 0)
+ if (priv)
{
- i2cdbg("Failed to register driver: %d\n", ret);
- free(priv);
+ priv->ops = &g_max1704xfopg;
+ priv->i2c = i2c;
+ priv->addr = addr;
}
- return ret;
+ return (FAR struct battery_lower_s *)priv;
}
-#endif /* CONFIG_I2C && CONFIG_I2C_MAX1704X */
+
+#endif /* CONFIG_BATTERY && CONFIG_I2C && CONFIG_I2C_MAX1704X */