Simplify upper-half battery driver

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4323 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-01-22 19:22:51 +00:00
parent 80ce244ce1
commit 8a4e17b865
3 changed files with 66 additions and 60 deletions

View File

@ -40,6 +40,7 @@
#include <nuttx/config.h>
#include <sempaphore.h>
#include <errno.h>
#include <debug.h>
@ -60,11 +61,6 @@
* Private
****************************************************************************/
struct bat_dev_s
{
FAR struct battery_lower_s *lower; /* The lower half battery driver */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
@ -81,7 +77,7 @@ static int bat_ioctl(FAR struct file *filep,int cmd,unsigned long arg);
* Private Data
****************************************************************************/
static const struct battery_operations_s g_max1704xfopg =
static const struct file_operations_s g_batteryops =
{
bat_open,
bat_close,
@ -101,7 +97,7 @@ static const struct battery_operations_s g_max1704xfopg =
* Name: bat_open
*
* Description:
* This function is called whenever theMAX1704x device is opened.
* This function is called whenever the battery device is opened.
*
****************************************************************************/
@ -114,7 +110,7 @@ static int bat_open(FAR struct file *filep)
* Name: bat_close
*
* Description:
* This routine is called when theMAX1704x device is closed.
* This routine is called when the battery device is closed.
*
****************************************************************************/
@ -129,6 +125,8 @@ static int bat_close(FAR struct file *filep)
static ssize_t bat_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
{
/* Return nothing read */
return 0;
}
@ -139,7 +137,9 @@ static ssize_t bat_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
static ssize_t bat_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -EACCESS;
/* Return nothing written */
return 0;
}
/****************************************************************************
@ -149,9 +149,20 @@ static ssize_t bat_write(FAR struct file *filep, FAR const char *buffer,
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;
FAR struct battery_dev_s *dev = inode->i_private;
int ret = -EINVAL;
/* Inforce mutually exclusive access to the battery driver */
ret = sem_wait(&dev->batsem);
if (ret < 0)
{
return -errno; /* Probably EINTR */
}
/* Procss the IOCTL command */
ret = -EINVAL; /* Assume a bad argument */
switch (cmd)
{
case BATIOC_STATE:
@ -159,7 +170,7 @@ static int bat_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
FAR int *ptr = (FAR int *)((uintptr_t)arg));
if (ptr)
{
*ptr = upper->state(priv->lower);
*ptr = dev->ops->state(dev);
ret = OK;
}
}
@ -169,7 +180,7 @@ static int bat_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
FAR bool *ptr = (FAR bool *)((uintptr_t)arg));
if (ptr)
{
*ptr = upper->online(priv->lower);
*ptr = dev->ops->online(dev);
ret = OK;
}
break;
@ -179,7 +190,7 @@ static int bat_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
FAR int *ptr = (FAR int *)((uintptr_t)arg));
if (ptr)
{
*ptr = upper->voltage(priv->lower);
*ptr = dev->ops->voltage(dev);
ret = OK;
}
}
@ -190,18 +201,19 @@ static int bat_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
FAR int *ptr = (FAR int *)((uintptr_t)arg));
if (ptr)
{
*ptr = upper->capacity(priv->lower);
*ptr = dev->ops->capacity(dev);
ret = OK;
}
}
break;
default:
i2cdbg("Unrecognized cmd: %d\n", cmd);
dbg("Unrecognized cmd: %d\n", cmd);
ret = -ENOTTY;
break;
}
sem_post(&dev->batsem);
return ret;
}
@ -219,36 +231,23 @@ static int bat_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
* 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.
* dev - An instance of the battery state structure .
*
* 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)
int battery_register(FAR const char *devpath, FAR struct battery_dev_s *dev)
{
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);
ret = register_driver(devpath, &g_batteryops, 0555, dev);
if (ret < 0)
{
i2cdbg("Failed to register driver: %d\n", ret);
free(upper);
dbg("Failed to register driver: %d\n", ret);
}
return ret;
}

View File

@ -67,6 +67,7 @@ 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 */
sem_t batsem; /* Enforce mutually exclusive access */
/* Data fields specific to the lower half MAX1704x driver follow */
@ -80,21 +81,21 @@ struct max1704x_dev_s
/* Battery driver lower half methods */
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);
static enum battery_status_e mx1704x_state(struct battery_dev_s *lower);
static bool mx1704x_online(struct battery_dev_s *lower);
static int mx1704x_voltage(struct battery_dev_s *lower);
static int mx1704x_capacity(struct battery_dev_s *lower);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct battery_operations_s g_max1704xfopg =
static const struct battery_operations_s g_max1704xops =
{
mx1704x_state,
mx1704x_online,
mx1704x_voltage,
mx1704x_capacity,
mx1704x_capacity
};
/****************************************************************************
@ -109,7 +110,7 @@ static const struct battery_operations_s g_max1704xfopg =
*
****************************************************************************/
static enum battery_status_e state(struct battery_lower_s *lower)
static enum battery_status_e state(struct battery_dev_s *lower)
{
#warning "Missing logic"
return BATTERY_UNKNOWN;
@ -123,7 +124,7 @@ static enum battery_status_e state(struct battery_lower_s *lower)
*
****************************************************************************/
static bool online(struct battery_lower_s *lower)
static bool online(struct battery_dev_s *lower)
{
#warning "Missing logic"
return false;
@ -137,7 +138,7 @@ static bool online(struct battery_lower_s *lower)
*
****************************************************************************/
static int voltage(struct battery_lower_s *lower);
static int voltage(struct battery_dev_s *lower);
{
#warning "Missing logic"
return 0;
@ -151,7 +152,7 @@ static int voltage(struct battery_lower_s *lower);
*
****************************************************************************/
static int capacity(struct battery_lower_s *lower);
static int capacity(struct battery_dev_s *lower);
{
#warning "Missing logic"
return 0;
@ -184,7 +185,7 @@ static int capacity(struct battery_lower_s *lower);
*
****************************************************************************/
FAR struct battery_lower_s *max1704x_initialize(FAR struct i2c_dev_s *i2c,
FAR struct battery_dev_s *max1704x_initialize(FAR struct i2c_dev_s *i2c,
uint8_t addr)
{
FAR struct max1704x_dev_s *priv;
@ -195,11 +196,12 @@ FAR struct battery_lower_s *max1704x_initialize(FAR struct i2c_dev_s *i2c,
priv = (FAR struct max1704x_dev_s *)kzalloc(sizeof(struct max1704x_dev_s));
if (priv)
{
priv->ops = &g_max1704xfopg;
sem_init(&priv->batsem, 0, 1);
priv->ops = &g_max1704xops;
priv->i2c = i2c;
priv->addr = addr;
}
return (FAR struct battery_lower_s *)priv;
return (FAR struct battery_dev_s *)priv;
}
#endif /* CONFIG_BATTERY && CONFIG_I2C && CONFIG_I2C_MAX1704X */

View File

@ -44,6 +44,8 @@
#include <nuttx/config.h>
#include <nuttx/ioctl.h>
#include <semaphore.h>
#ifdef CONFIG_BATTERY
/****************************************************************************
@ -99,33 +101,36 @@ enum battery_status_e
/* This structure defines the lower half battery interface */
struct battery_lower_s;
struct battery_dev_s;
struct battery_operations_s
{
/* Return the current battery state */
enum battery_status_e state(struct battery_lower_s *lower);
enum battery_status_e state(struct battery_dev_s *dev);
/* Return true if the batter is online */
bool online(struct battery_lower_s *lower);
bool online(struct battery_dev_s *dev);
/* Current battery voltage */
int voltage(struct battery_lower_s *lower);
int voltage(struct battery_dev_s *dev);
/* Battery capacity */
int capacity(struct battery_lower_s *lower);
int capacity(struct battery_dev_s *dev);
};
/* This structure defines the lower half battery driver state structure */
/* This structure defines the battery driver state structure */
struct battery_lower_s
struct battery_dev_s
{
FAR const struct battery_operations_s *ops; /* Battery operations */
/* Fields required by the upper-half driver */
/* Data fields specific to the lower half driver may follow */
FAR const struct battery_operations_s *ops; /* Battery operations */
sem_t batsem; /* Enforce mutually exclusive access */
/* Data fields specific to the lower-half driver may follow */
};
/****************************************************************************
@ -154,7 +159,7 @@ extern "C" {
* 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.
* dev - An instance of the battery state structure .
*
* Returned value:
* Zero on success or a negated errno value on failure.
@ -162,7 +167,7 @@ extern "C" {
****************************************************************************/
EXTERN int battery_register(FAR const char *devpath,
FAR struct battery_lower_s *lower);
FAR struct battery_dev_s *dev);
/****************************************************************************
* Name: max1704x_initialize
@ -182,13 +187,13 @@ EXTERN int battery_register(FAR const char *devpath,
* addr - The I2C address of the MAX1704x.
*
* Returned Value:
* A pointer to the intialized lower-half driver instance. A NULL pointer
* A pointer to the intialized battery driver instance. A NULL pointer
* is returned on a failure to initialize the MAX1704x lower half.
*
****************************************************************************/
#if defined(CONFIG_I2C) && defined(CONFIG_I2C_MAX1704X)
EXTERN FAR struct battery_lower_s *
EXTERN FAR struct battery_dev_s *
max1704x_initialize(FAR struct i2c_dev_s *i2c, uint8_t addr);
#endif