1
0
Fork 0
forked from nuttx/nuttx-update

Battery Charger: Add BQ24250 driver

This commit is contained in:
Alan Carvalho de Assis 2015-09-20 09:47:00 -06:00 committed by Gregory Nutt
parent d4fc91d6f6
commit c52e3e017b
7 changed files with 1095 additions and 10 deletions

View file

@ -10979,4 +10979,6 @@
* drivers/power/battery_charter.c and include/nuttx/power/batter_charger.h:
Add a new frame to support a batter charger interface. From Alan
Carvalho de Assis (2015-09-19).
* drivers/power/bq2425x.c and .h: Battery Charger: Add BQ24250 driver.
From Alan Carvalho de Assis (2015-09-20).

View file

@ -7,12 +7,21 @@ config BATTERY_CHARGER
bool "Battery Charger support"
default n
config BQ2425X
bool "BQ2425X Battery charger support"
default n
select I2C
select I2C_BQ2425X
depends on BATTERY_CHARGER
---help---
The BQ24250/BQ24251 are battery charger for lithium-ion batteries.
config BATTERY_GAUGE
bool "Battery Fuel Gauge support"
default n
config MAX1704X
bool "MAX1704X Battery charger support"
bool "MAX1704X Battery fuel gauge support"
default n
select I2C
select I2C_MAX1704X
@ -23,6 +32,10 @@ config MAX1704X
The MAX17040 is configured to operate with a single lithium cell and the
MAX17041 is configured for a dual-cell 2S pack.
config I2C_BQ2425X
bool
default y if BQ2425X
config I2C_MAX1704X
bool
default y if MAX1704X

View file

@ -41,7 +41,8 @@ POWER_CFLAGS =
ifeq ($(CONFIG_PM),y)
CSRCS += pm_activity.c pm_changestate.c pm_checkstate.c pm_initialize.c pm_register.c pm_update.c
CSRCS += pm_activity.c pm_changestate.c pm_checkstate.c pm_initialize.c
CSRCS += pm_register.c pm_update.c
# Include power management in the build
@ -51,21 +52,43 @@ POWER_CFLAGS := ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$
endif
# Add battery drivers
# Add battery charger drivers
ifeq ($(CONFIG_BATTERY_CHARGER),y)
CSRCS += battery_charger.c
# Add I2C-based battery charger drivers
ifeq ($(CONFIG_I2C),y)
# Add the BQ2425x I2C-based battery charger driver
ifeq ($(CONFIG_I2C_BQ2425X),y)
CSRCS += bq2425x.c
endif
endif
# Include battery suport in the build
POWER_DEPPATH := --dep-path power
POWER_VPATH := :power
POWER_CFLAGS := ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)power}
endif
# Add battery gauge drivers
ifeq ($(CONFIG_BATTERY_GAUGE),y)
CSRCS += battery_gauge.c
# Add I2C-based battery drivers
# Add I2C-based battery gauge drivers
ifeq ($(CONFIG_I2C),y)
# Add the MAX1704x I2C-based battery driver
# Add the MAX1704x I2C-based battery guage driver
ifeq ($(CONFIG_I2C_MAX1704X),y)
CSRCS += max1704x.c

View file

@ -207,9 +207,9 @@ static int bat_charger_ioctl(FAR struct file *filep, int cmd,
{
int volts;
FAR int *voltsp = (FAR int *)((uintptr_t)arg);
volts = *voltsp;
if (ptr)
if (voltsp)
{
volts = *voltsp;
ret = dev->ops->voltage(dev, volts);
}
}
@ -219,9 +219,9 @@ static int bat_charger_ioctl(FAR struct file *filep, int cmd,
{
int amps;
FAR int *ampsp = (FAR int *)((uintptr_t)arg);
amps = *ampsp;
if (ptr)
if (ampsp)
{
amps = *ampsp;
ret = dev->ops->current(dev, amps);
}
}

775
drivers/power/bq2425x.c Normal file
View file

@ -0,0 +1,775 @@
/****************************************************************************
* drivers/power/bq2425x.c
* Lower half driver for BQ2425x battery charger
*
* Copyright (C) 2015 Alan Carvalho de Assis. All rights reserved.
* Author: Alan Carvalho de Assis <acassis@gmail.com>
*
* 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.
*
****************************************************************************/
/* The BQ24250/BQ24251 are Li-Ion Battery Charger with Power-Path Management.
* It can be configured to Input Current Limit up to 2A.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <unistd.h>
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/kmalloc.h>
#include <nuttx/i2c.h>
#include <nuttx/power/battery_charger.h>
#include <nuttx/power/battery_ioctl.h>
#include "bq2425x.h"
/* This driver requires:
*
* CONFIG_BATTERY_CHARGER - Upper half battery driver support
* CONFIG_I2C - I2C support
* CONFIG_I2C_BQ2425X - And the driver must be explictly selected.
*/
#if defined(CONFIG_BATTERY_CHARGER) && defined(CONFIG_I2C) && \
defined(CONFIG_I2C_BQ2425X)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Debug ********************************************************************/
#ifdef CONFIG_DEBUG_BQ2425X
# define batdbg dbg
#else
# ifdef CONFIG_CPP_HAVE_VARARGS
# define batdbg(x...)
# else
# define batdbg (void)
# endif
#endif
/****************************************************************************
* Private
****************************************************************************/
struct bq2425x_dev_s
{
/* The common part of the battery driver visible to the upper-half driver */
FAR const struct battery_charger_operations_s *ops; /* Battery operations */
sem_t batsem; /* Enforce mutually exclusive access */
/* Data fields specific to the lower half BQ2425x driver follow */
FAR struct i2c_dev_s *i2c; /* I2C interface */
uint8_t addr; /* I2C address */
uint32_t frequency; /* I2C frequency */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/* I2C support */
static int bq2425x_getreg8(FAR struct bq2425x_dev_s *priv, uint8_t regaddr,
FAR uint8_t *regval);
static int bq2425x_putreg8(FAR struct bq2425x_dev_s *priv, uint8_t regaddr,
uint8_t regval);
static inline int bq2425x_getreport(FAR struct bq2425x_dev_s *priv,
uint8_t *report);
static inline int bq2425x_reset(FAR struct bq2425x_dev_s *priv);
static inline int bq2425x_watchdog(FAR struct bq2425x_dev_s *priv, bool enable);
static inline int bq2425x_setvolt(FAR struct bq2425x_dev_s *priv, int volts);
static inline int bq2425x_setcurr(FAR struct bq2425x_dev_s *priv, int current);
/* Battery driver lower half methods */
static int bq2425x_state(struct battery_charger_dev_s *dev, int *status);
static int bq2425x_health(struct battery_charger_dev_s *dev, int *health);
static int bq2425x_online(struct battery_charger_dev_s *dev, bool *status);
static int bq2425x_voltage(struct battery_charger_dev_s *dev, int value);
static int bq2425x_current(struct battery_charger_dev_s *dev, int value);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct battery_charger_operations_s g_bq2425xops =
{
bq2425x_state,
bq2425x_health,
bq2425x_online,
bq2425x_voltage,
bq2425x_current
};
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: bq2425x_getreg8
*
* Description:
* Read a 8-bit value from a BQ2425x register pair.
*
* START <I2C write address> ACK <Reg address> ACK
* REPEATED-START <I2C read address> ACK Data0 ACK Data1 NO-ACK STOP
*
****************************************************************************/
static int bq2425x_getreg8(FAR struct bq2425x_dev_s *priv, uint8_t regaddr,
FAR uint8_t *regval)
{
uint8_t val;
int ret;
/* Set the I2C address and address size */
I2C_SETADDRESS(priv->i2c, priv->addr, 7);
/* Write the register address */
ret = I2C_WRITE(priv->i2c, &regaddr, 1);
if (ret < 0)
{
batdbg("I2C_WRITE failed: %d\n", ret);
return ret;
}
/* Restart and read 8-bits from the register */
ret = I2C_READ(priv->i2c, &val, 1);
if (ret < 0)
{
batdbg("I2C_READ failed: %d\n", ret);
return ret;
}
/* Copy 8-bit value to be returned */
*regval = val;
return OK;
}
/****************************************************************************
* Name: bq2425x_putreg8
*
* Description:
* Write a 8-bit value to a BQ2425x register pair.
*
* START <I2C write address> ACK <Reg address> ACK Data0 ACK Data1 ACK STOP
*
****************************************************************************/
static int bq2425x_putreg8(FAR struct bq2425x_dev_s *priv, uint8_t regaddr,
uint8_t regval)
{
uint8_t buffer[2];
batdbg("addr: %02x regval: %08x\n", regaddr, regval);
/* Set up a 3 byte message to send */
buffer[0] = regaddr;
buffer[1] = regval;
/* Set the I2C address and address size */
I2C_SETADDRESS(priv->i2c, priv->addr, 7);
/* Write the register address followed by the data (no RESTART) */
return I2C_WRITE(priv->i2c, buffer, 2);
}
/****************************************************************************
* Name: bq2425x_getreport
*
* Description:
* Read the BQ2425X Register #1 (status and fault)
*
****************************************************************************/
static inline int bq2425x_getreport(FAR struct bq2425x_dev_s *priv,
uint8_t *report)
{
uint8_t regval = 0;
int ret;
ret = bq2425x_getreg8(priv, BQ2425X_REG_1, &regval);
if (ret == OK)
{
*report = regval;
}
return ret;
}
/****************************************************************************
* Name: bq2425x_reset
*
* Description:
* Reset the BQ2425x
*
****************************************************************************/
static inline int bq2425x_reset(FAR struct bq2425x_dev_s *priv)
{
int ret;
uint8_t regval;
/* Read current register value */
ret = bq2425x_getreg8(priv, BQ2425X_REG_2, &regval);
if (ret < 0)
{
batdbg("Error reading from BQ2425X! Error = %d\n", ret);
return ret;
}
/* Send reset command */
regval |= BQ2425X_RESET;
ret = bq2425x_putreg8(priv, BQ2425X_REG_2, regval);
if (ret < 0)
{
batdbg("Error writing to BQ2425X! Error = %d\n", ret);
return ret;
}
/* Wait a little bit to clear registers */
usleep(500);
/* There is a BUG in BQ2425X the RESET bit is always read as 1 */
regval &= ~(BQ2425X_RESET);
ret = bq2425x_putreg8(priv, BQ2425X_REG_2, regval);
if (ret < 0)
{
batdbg("Error writing to BQ2425X! Error = %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bq2425x_watchdog
*
* Description:
* Enable/Disable the BQ2425x watchdog
*
****************************************************************************/
static inline int bq2425x_watchdog(FAR struct bq2425x_dev_s *priv, bool enable)
{
int ret;
uint8_t regval;
ret = bq2425x_getreg8(priv, BQ2425X_REG_1, &regval);
if (ret < 0)
{
batdbg("Error reading from BQ2425X! Error = %d\n", ret);
return ret;
}
if (enable)
{
regval |= BQ2425X_WD_EN;
}
else
{
regval &= ~(BQ2425X_WD_EN);
}
ret = bq2425x_putreg8(priv, BQ2425X_REG_1, regval);
if (ret < 0)
{
batdbg("Error writing to BQ2425X! Error = %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bq2425x_state
*
* Description:
* Return the current battery state
*
****************************************************************************/
static int bq2425x_state(struct battery_charger_dev_s *dev, int *status)
{
FAR struct bq2425x_dev_s *priv = (FAR struct bq2425x_dev_s *)dev;
uint8_t regval = 0;
int ret;
ret = bq2425x_getreport(priv, &regval);
if (ret < 0)
{
*status = BATTERY_UNKNOWN;
return ret;
}
regval &= BQ2425X_STAT_MASK;
/* Is there some fault in the battery? */
if (regval == BQ2425X_STAT_FAULT)
{
*status = BATTERY_FAULT;
}
/* Is the charging done? */
else if (regval == BQ2425X_STAT_CHG_DONE)
{
*status = BATTERY_FULL;
}
/* Is the charging in progress? */
else if (regval == BQ2425X_STAT_CHG_PROGRESS)
{
*status = BATTERY_CHARGING;
}
/* Is the charging ready? */
else if (regval == BQ2425X_STAT_READY)
{
*status = BATTERY_IDLE;
}
return OK;
}
/****************************************************************************
* Name: bq2425x_health
*
* Description:
* Return the current battery health state
*
* Note: if more than one fault happened the user needs to call this ioctl
* again to read a new fault, repeat until receive a BATTERY_HEALTH_GOOD.
*
****************************************************************************/
static int bq2425x_health(struct battery_charger_dev_s *dev, int *health)
{
FAR struct bq2425x_dev_s *priv = (FAR struct bq2425x_dev_s *)dev;
uint8_t regval = 0;
int ret;
ret = bq2425x_getreport(priv, &regval);
if (ret < 0)
{
*health = BATTERY_HEALTH_UNKNOWN;
return ret;
}
regval &= BQ2425X_FAULT_MASK;
switch (regval)
{
case BQ2425X_FAULT_NORMAL:
*health = BATTERY_HEALTH_GOOD;
break;
case BQ2425X_FAULT_SLEEP:
case BQ2425X_FAULT_INP_OVP:
case BQ2425X_FAULT_INP_UVLO:
case BQ2425X_FAULT_ISET_SHORT:
case BQ2425X_FAULT_INP_LDO_LOW:
*health = BATTERY_HEALTH_UNSPEC_FAIL;
break;
case BQ2425X_FAULT_BAT_OVP:
*health = BATTERY_HEALTH_OVERVOLTAGE;
break;
case BQ2425X_FAULT_BAT_TEMP:
case BQ2425X_FAULT_THERM_SHUT:
*health = BATTERY_HEALTH_OVERHEAT;
break;
case BQ2425X_FAULT_TIMER:
*health = BATTERY_HEALTH_SAFE_TMR_EXP;
break;
case BQ2425X_FAULT_NO_BATTERY:
*health = BATTERY_HEALTH_DISCONNECTED;
break;
default:
*health = BATTERY_HEALTH_UNKNOWN;
break;
}
return OK;
}
/****************************************************************************
* Name: bq2425x_online
*
* Description:
* Return true if the battery is online
*
****************************************************************************/
static int bq2425x_online(struct battery_charger_dev_s *dev, bool *status)
{
/* There is no concept of online/offline in this driver */
*status = true;
return OK;
}
/****************************************************************************
* Name: bq2425x_powersupply
*
* Description:
* Set the Power Supply Current Limit.
*
****************************************************************************/
static inline int bq2425x_powersupply(FAR struct bq2425x_dev_s *priv, int current)
{
uint8_t regval;
int ret, idx;
switch (current)
{
case 100:
idx = BQ2425X_INP_CURR_LIM_100MA;
break;
case 150:
idx = BQ2425X_INP_CURR_LIM_150MA;
break;
case 500:
idx = BQ2425X_INP_CURR_LIM_500MA;
break;
case 900:
idx = BQ2425X_INP_CURR_LIM_900MA;
break;
case 1500:
idx = BQ2425X_INP_CURR_LIM_1500MA;
break;
case 2000:
idx = BQ2425X_INP_CURR_LIM_2000MA;
break;
default:
batdbg("Current not supported, setting default to 100mA.!\n");
idx = BQ2425X_INP_CURR_LIM_100MA;
break;
}
/* Read current register */
ret = bq2425x_getreg8(priv, BQ2425X_REG_2, &regval);
if (ret < 0)
{
batdbg("Error reading from BQ2425X! Error = %d\n", ret);
return ret;
}
/* Clear previous current and set new value */
regval &= ~(BQ2425X_INP_CURR_LIM_MASK);
regval |= idx;
/* Also clear Reset bit to avoid the resetting BUG */
regval &= ~(BQ2425X_RESET);
ret = bq2425x_putreg8(priv, BQ2425X_REG_2, regval);
if (ret < 0)
{
batdbg("Error writing to BQ2425X! Error = %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bq2425x_setvolt
*
* Description:
* Set the voltage level to charge the battery. Voltage value in mV.
*
****************************************************************************/
static inline int bq2425x_setvolt(FAR struct bq2425x_dev_s *priv, int volts)
{
uint8_t regval;
int ret, idx;
/* Verify if voltage is in the acceptable range */
if (volts < BQ2425X_VOLT_MIN || volts > BQ2425X_VOLT_MAX)
{
batdbg("Voltage %d mV is out of range.\n", volts);
return -EINVAL;
}
ret = bq2425x_getreg8(priv, BQ2425X_REG_3, &regval);
if (ret < 0)
{
batdbg("Error reading from BQ2425X! Error = %d\n", ret);
return ret;
}
/* Voltage starts at 3500mV and increases in steps of 20mV */
idx = volts - BQ2425X_VOLT_MIN;
idx = idx / 20;
/* Clear previous voltage */
regval &= ~(BQ2425X_BAT_VOLT_MASK);
regval |= (idx << BQ2425X_BAT_VOLT_SHIFT);
ret = bq2425x_putreg8(priv, BQ2425X_REG_3, regval);
if (ret < 0)
{
batdbg("Error writing to BQ2425X! Error = %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bq2425x_setcurr
*
* Description:
* Set the current to charge the battery. Current value in mA.
*
****************************************************************************/
static inline int bq2425x_setcurr(FAR struct bq2425x_dev_s *priv, int current)
{
uint8_t regval;
int ret, idx;
/* Verify if voltage is in the acceptable range */
if (current < BQ2425X_CURR_MIN || current > BQ2425X_CURR_MAX)
{
batdbg("Current %d mA is out of range.\n", volts);
return -EINVAL;
}
ret = bq2425x_getreg8(priv, BQ2425X_REG_4, &regval);
if (ret < 0)
{
batdbg("Error reading from BQ2425X! Error = %d\n", ret);
return ret;
}
/* Current starts at 500mV and increases in steps of 50mA */
idx = current - BQ2425X_CURR_MIN;
idx = idx / 50;
/* Clear previous current and set new value */
regval &= ~(BQ2425X_CHG_CURRENT_MASK);
regval |= (idx << BQ2425X_CHG_CURRENT_SHIFT);
ret = bq2425x_putreg8(priv, BQ2425X_REG_4, regval);
if (ret < 0)
{
batdbg("Error writing to BQ2425X! Error = %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bq2425x_voltage
*
* Description:
* Set battery charger voltage
*
****************************************************************************/
static int bq2425x_voltage(struct battery_charger_dev_s *dev, int value)
{
FAR struct bq2425x_dev_s *priv = (FAR struct bq2425x_dev_s *)dev;
int ret;
/* Set voltage to battery charger */
ret = bq2425x_setvolt(priv, value);
if (ret < 0)
{
batdbg("Error setting voltage to BQ2425X! Error = %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bq2425x_current
*
* Description:
* Set the battery charger current rate for charging
*
****************************************************************************/
static int bq2425x_current(struct battery_charger_dev_s *dev, int value)
{
FAR struct bq2425x_dev_s *priv = (FAR struct bq2425x_dev_s *)dev;
int ret;
/* Set current to battery charger */
ret = bq2425x_setcurr(priv, value);
if (ret < 0)
{
batdbg("Error setting current to BQ2425X! Error = %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: bq2425x_initialize
*
* Description:
* Initialize the BQ2425x battery driver and return an instance of the
* lower_half interface that may be used with battery_charger_register();
*
* This driver requires:
*
* CONFIG_BATTERY_CHARGER - Upper half battery driver support
* CONFIG_I2C - I2C support
* CONFIG_I2C_BQ2425X - And the driver must be explictly selected.
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* the BQ2425x
* addr - The I2C address of the BQ2425x (Better be 0x36).
* frequency - The I2C frequency
*
* Returned Value:
* A pointer to the initializeed lower-half driver instance. A NULL pointer
* is returned on a failure to initialize the BQ2425x lower half.
*
****************************************************************************/
FAR struct battery_charger_dev_s *bq2425x_initialize(FAR struct i2c_dev_s *i2c,
uint8_t addr, uint32_t frequency)
{
FAR struct bq2425x_dev_s *priv;
int ret;
/* Initialize the BQ2425x device structure */
priv = (FAR struct bq2425x_dev_s *)kmm_zalloc(sizeof(struct bq2425x_dev_s));
if (priv)
{
/* Initialize the BQ2425x device structure */
sem_init(&priv->batsem, 0, 1);
priv->ops = &g_bq2425xops;
priv->i2c = i2c;
priv->addr = addr;
priv->frequency = frequency;
/* Set the I2C frequency (ignoring the returned, actual frequency) */
(void)I2C_SETFREQUENCY(i2c, priv->frequency);
/* Reset the BQ2425x */
ret = bq2425x_reset(priv);
if (ret < 0)
{
batdbg("Failed to reset the BQ2425x: %d\n", ret);
kmm_free(priv);
return NULL;
}
/* Disable watchdog otherwise BQ2425x returns to StandAlone mode */
ret = bq2425x_watchdog(priv, false);
if (ret < 0)
{
batdbg("Failed to disable BQ2425x watchdog: %d\n", ret);
kmm_free(priv);
return NULL;
}
/* Define that our power supply can offer 2000mA to the charger */
ret = bq2425x_powersupply(priv, 2000);
if (ret < 0)
{
batdbg("Failed to set BQ2425x power supply current: %d\n", ret);
kmm_free(priv);
return NULL;
}
}
return (FAR struct battery_charger_dev_s *)priv;
}
#endif /* CONFIG_BATTERY && CONFIG_I2C && CONFIG_I2C_BQ2425X */

272
drivers/power/bq2425x.h Normal file
View file

@ -0,0 +1,272 @@
/****************************************************************************
* drivers/power/bq2425x.h
* Lower half driver for BQ2425x battery charger
*
* Copyright (C) 2015 Alan Carvalho de Assis. All rights reserved.
* Author: Alan Carvalho de Assis <acassis@gmail.com>
*
* 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.
*
****************************************************************************/
#ifndef __DRIVERS_POWER_BQ2425X_H
#define __DRIVERS_POWER_BQ2425X_H
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Auxiliary Definitions */
#define BQ2425X_VOLT_MIN 3500
#define BQ2425X_VOLT_MAX 4440
#define BQ2425X_CURR_MIN 500
#define BQ2425X_CURR_MAX 2000
/* BQ2425x Register Definitions ********************************************/
#define BQ2425X_REG_1 0x00
#define BQ2425X_REG_2 0x01
#define BQ2425X_REG_3 0x02
#define BQ2425X_REG_4 0x03
#define BQ2425X_REG_5 0x04
#define BQ2425X_REG_6 0x05
#define BQ2425X_REG_7 0x06
/* REG 1 */
#define BQ2425X_WD_FAULT (1 << 7) /* If 1 means WD timeout if WD is enabled */
#define BQ2425X_WD_EN (1 << 6) /* Set 1 will enable and reset timeout */
#define BQ2425X_STAT_SHIFT 4 /* Battery charger status */
#define BQ2425X_STAT_MASK (3 << BQ2425X_STAT_SHIFT)
# define BQ2425X_STAT_READY (0 << BQ2425X_STAT_SHIFT)
# define BQ2425X_STAT_CHG_PROGRESS (1 << BQ2425X_STAT_SHIFT)
# define BQ2425X_STAT_CHG_DONE (2 << BQ2425X_STAT_SHIFT)
# define BQ2425X_STAT_FAULT (3 << BQ2425X_STAT_SHIFT)
#define BQ2425X_FAULT_SHIFT 0 /* Battery Fault report */
#define BQ2425X_FAULT_MASK (15 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_NORMAL (0 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_INP_OVP (1 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_INP_UVLO (2 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_SLEEP (3 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_BAT_TEMP (4 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_BAT_OVP (5 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_THERM_SHUT (6 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_TIMER (7 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_NO_BATTERY (8 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_ISET_SHORT (9 << BQ2425X_FAULT_SHIFT)
# define BQ2425X_FAULT_INP_LDO_LOW (10 << BQ2425X_FAULT_SHIFT)
/* REG 2 */
#define BQ2425X_RESET (1 << 7) /* Write 1 to Reset all register to default values */
#define BQ2425X_INP_CURR_LIM_SHIFT 4 /* Input Current Limit */
#define BQ2425X_INP_CURR_LIM_MASK (7 << BQ2425X_INP_CURR_LIM_SHIFT)
# define BQ2425X_INP_CURR_LIM_100MA (0 << BQ2425X_INP_CURR_LIM_SHIFT) /* USB2.0 host with 100mA current limit */
# define BQ2425X_INP_CURR_LIM_150MA (1 << BQ2425X_INP_CURR_LIM_SHIFT) /* USB3.0 host with 150mA current limit */
# define BQ2425X_INP_CURR_LIM_500MA (2 << BQ2425X_INP_CURR_LIM_SHIFT) /* USB2.0 host with 500mA current limit */
# define BQ2425X_INP_CURR_LIM_900MA (3 << BQ2425X_INP_CURR_LIM_SHIFT) /* USB3.0 host with 900mA current limit */
# define BQ2425X_INP_CURR_LIM_1500MA (4 << BQ2425X_INP_CURR_LIM_SHIFT) /* Charger with 1500mA current limit */
# define BQ2425X_INP_CURR_LIM_2000MA (5 << BQ2425X_INP_CURR_LIM_SHIFT) /* Charger with 2000mA current limit */
# define BQ2425X_INP_CURR_EXT_ILIM (6 << BQ2425X_INP_CURR_LIM_SHIFT) /* External ILIM current limit */
# define BQ2425X_INP_CURR_NO_LIMIT (7 << BQ2425X_INP_CURR_LIM_SHIFT) /* No input current limit with internal clamp at 3A */
#define BQ2425X_EN_STAT (1 << 3) /* Enable/Disable STAT pin */
#define BQ2425X_EN_TERM (1 << 2) /* Enable/Disable charge termination */
#define BQ2425X_CE (1 << 1) /* Enable/Disable the Charger, inverted logic, 0 enables */
#define BQ2425X_HZ_MODE (1 << 0) /* Sets the charger IC into low power standby mode, but keep BAT FET ON */
/* REG 3 */
#define BQ2425X_BAT_VOLT_SHIFT 2
#define BQ2425X_BAT_VOLT_MASK (0x3F << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3500MV (0 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3520MV (1 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3540MV (2 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3560MV (3 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3580MV (4 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3600MV (5 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3620MV (6 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3640MV (7 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3660MV (8 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3680MV (9 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3700MV (10 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3720MV (11 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3740MV (12 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3760MV (13 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3780MV (14 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3800MV (15 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3820MV (16 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3840MV (17 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3860MV (18 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3880MV (19 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3900MV (20 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3920MV (21 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3940MV (22 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3960MV (23 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_3980MV (24 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4000MV (25 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4020MV (26 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4040MV (27 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4060MV (28 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4080MV (29 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4100MV (30 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4120MV (31 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4140MV (32 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4160MV (33 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4180MV (34 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4200MV (35 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4220MV (36 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4240MV (37 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4260MV (38 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4280MV (39 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4300MV (40 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4320MV (41 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4340MV (42 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4360MV (43 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4380MV (44 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4400MV (45 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4420MV (46 << BQ2425X_BAT_VOLT_SHIFT)
# define BQ2425X_BAT_VOLT_4440MV (47 << BQ2425X_BAT_VOLT_SHIFT)
#define BQ2425X_USB_DET_EN_SHIFT 0
#define BQ2425X_USB_DET_EN_MASK (3 << BQ2425X_USB_DET_EN_SHIFT)
# define BQ2425X_DCP_EN2_0_EN1_0 (0 << BQ2425X_USB_DET_EN_SHIFT)
# define BQ2425X_CDP_EN2_0_EN1_1 (1 << BQ2425X_USB_DET_EN_SHIFT)
# define BQ2425X_SDP_EN2_1_EN1_0 (2 << BQ2425X_USB_DET_EN_SHIFT)
# define BQ2425X_APPLE_EN2_1_EN1_1 (3 << BQ2425X_USB_DET_EN_SHIFT)
/* REG 4 */
#define BQ2425X_CHG_CURRENT_SHIFT 2
#define BQ2425X_CHG_CURRENT_MASK (0x1F << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_500MA (0 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_550MA (1 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_600MA (2 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_650MA (3 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_700MA (4 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_750MA (5 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_800MA (6 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_850MA (7 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_900MA (8 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_950MA (9 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1000MA (10 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1050MA (11 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1100MA (12 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1150MA (13 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1200MA (14 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1250MA (15 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1300MA (16 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1350MA (17 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1400MA (18 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1450MA (19 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1500MA (20 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1550MA (21 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1600MA (22 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1650MA (23 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1700MA (24 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1750MA (25 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1800MA (26 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1850MA (27 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1900MA (28 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_1950MA (29 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_CURRENT_2000MA (30 << BQ2425X_CHG_CURRENT_SHIFT)
# define BQ2425X_CHG_EXT_ISET_MODE (31 << BQ2425X_CHG_CURRENT_SHIFT)
#define BQ2425X_CHG_CURR_TERM_SHIFT 0
#define BQ2425X_CHG_CURR_TERM_MASK (7 << BQ2425X_CHG_CURR_TERM_SHIFT)
# define BQ2425X_CHG_CURR_TERM_50MA (0 << BQ2425X_CHG_CURR_TERM_SHIFT)
# define BQ2425X_CHG_CURR_TERM_75MA (1 << BQ2425X_CHG_CURR_TERM_SHIFT)
# define BQ2425X_CHG_CURR_TERM_100MA (2 << BQ2425X_CHG_CURR_TERM_SHIFT)
# define BQ2425X_CHG_CURR_TERM_125MA (3 << BQ2425X_CHG_CURR_TERM_SHIFT)
# define BQ2425X_CHG_CURR_TERM_150MA (4 << BQ2425X_CHG_CURR_TERM_SHIFT)
# define BQ2425X_CHG_CURR_TERM_175MA (5 << BQ2425X_CHG_CURR_TERM_SHIFT)
# define BQ2425X_CHG_CURR_TERM_200MA (6 << BQ2425X_CHG_CURR_TERM_SHIFT)
# define BQ2425X_CHG_CURR_TERM_225MA (7 << BQ2425X_CHG_CURR_TERM_SHIFT)
/* REG 5 */
#define BQ2425X_LOOP_STATUS_SHIFT 6 /* Show if there is some active loop that slow down safety timer */
#define BQ2425X_LOOP_STATUS_MASK (3 << BQ2425X_LOOP_STATUS_SHIFT)
# define BQ2425X_NO_LOOP (0 << BQ2425X_LOOP_STATUS_SHIFT)
# define BQ2425X_VIN_DPM_LOOP (1 << BQ2425X_LOOP_STATUS_SHIFT)
# define BQ2425X_INP_CURR_LIM_LOOP (2 << BQ2425X_LOOP_STATUS_SHIFT)
# define BQ2425X_THERM_REG_LOOP (3 << BQ2425X_LOOP_STATUS_SHIFT)
#define BQ2425X_LOW_CHG (1 << 5) /* 0 = REG 4 defines current; 1 = Low curr 330mA */
#define BQ2425X_DPDM_EN (1 << 4) /* Force D+/D- detection */
#define BQ2425X_CE_STATUS (1 << 3) /* 0 = CE low ; 1 = CE high */
#define BQ2425X_VIN_DPM_SHIFT 0 /* Sets the input VDPM level */
#define BQ2425X_VIN_DPM_MASK (7 << BQ2425X_VIN_DPM_SHIFT)
# define BQ2425X_VIN_DPM_4200MV (0 << BQ2425X_VIN_DPM_SHIFT)
# define BQ2425X_VIN_DPM_4280MV (1 << BQ2425X_VIN_DPM_SHIFT)
# define BQ2425X_VIN_DPM_4360MV (2 << BQ2425X_VIN_DPM_SHIFT)
# define BQ2425X_VIN_DPM_4440MV (3 << BQ2425X_VIN_DPM_SHIFT)
# define BQ2425X_VIN_DPM_4520MV (4 << BQ2425X_VIN_DPM_SHIFT)
# define BQ2425X_VIN_DPM_4600MV (5 << BQ2425X_VIN_DPM_SHIFT)
# define BQ2425X_VIN_DPM_4680MV (5 << BQ2425X_VIN_DPM_SHIFT)
# define BQ2425X_VIN_DPM_4760MV (5 << BQ2425X_VIN_DPM_SHIFT)
/* REG 6 */
#define BQ2425X_2XTMR_EN (1 << 7) /* Timer slowed 2x when in thermal reg., Vin_dpm or DPPM */
#define BQ2425X_TIMER_SHIFT 6 /* Safety timer time limit */
#define BQ2425X_TIMER_MASK (3 << BQ2425X_TIMER_SHIFT)
# define BQ2425X_TIMER_0p74H (0 << BQ2425X_TIMER_SHIFT) /* 0.75 hour fast charge */
# define BQ2425X_TIMER_6H (1 << BQ2425X_TIMER_SHIFT) /* 6 hour fast charge (default 01) */
# define BQ2425X_TIMER_9H (2 << BQ2425X_TIMER_SHIFT) /* 9 hour fast charge */
# define BQ2425X_TIMER_DISABLED (3 << BQ2425X_TIMER_SHIFT) /* Disable safety timers */
#define BQ2425X_SYSOFF (1 << 4) /* 0 = SYSOFF disabled ; 1 = SYSOFF enabled */
#define BQ2425X_TS_EN (1 << 3) /* 0 = TS function disabled ; 1 = TS function enabled */
#define BQ2425X_TS_STATUS_SHIFT 0 /* TS Fault Mode */
#define BQ2425X_TS_STATUS_MASK (7 << BQ2425X_TS_STATUS_SHIFT)
# define BQ2425X_TS_NORMAL (0 << BQ2425X_TS_STATUS_SHIFT) /* Normal, No TS fault */
# define BQ2425X_TS_TEMP_HOT (1 << BQ2425X_TS_STATUS_SHIFT) /* TS_temp > T_hot */
# define BQ2425X_TS_TEMP_WARM (2 << BQ2425X_TS_STATUS_SHIFT) /* T_warm < TS_temp < T_hot */
# define BQ2425X_TS_TEMP_COOL (3 << BQ2425X_TS_STATUS_SHIFT) /* T_cold < TS_temp < T_cool*/
# define BQ2425X_TS_TEMP_COLD (4 << BQ2425X_TS_STATUS_SHIFT) /* TS_temp < T_cold */
# define BQ2425X_TS_TEMP_VERY_COLD (5 << BQ2425X_TS_STATUS_SHIFT) /* T_freeze < TS_temp < T_cold */
# define BQ2425X_TS_TEMP_FREEZE (6 << BQ2425X_TS_STATUS_SHIFT) /* TS_temp < T_freeze */
# define BQ2425X_TS_OPEN_DISABLED (7 << BQ2425X_TS_STATUS_SHIFT) /* TS open (TS disabled) */
/* REG 7 */
#define BQ2425X_VOLT_OVP_SHIFT 5 /* OVP voltage */
#define BQ2425X_VOLT_OVP_MASK (7 << BQ2425X_VOLT_OVP_SHIFT)
# define BQ2425X_VOLT_OVP_6p0V (0 << BQ2425X_VOLT_OVP_SHIFT) /* 6.0V */
# define BQ2425X_VOLT_OVP_6p5V (1 << BQ2425X_VOLT_OVP_SHIFT) /* 6.5V */
# define BQ2425X_VOLT_OVP_7p0V (2 << BQ2425X_VOLT_OVP_SHIFT) /* 7.0V */
# define BQ2425X_VOLT_OVP_8p0V (3 << BQ2425X_VOLT_OVP_SHIFT) /* 8.0V */
# define BQ2425X_VOLT_OVP_9p0V (4 << BQ2425X_VOLT_OVP_SHIFT) /* 9.0V */
# define BQ2425X_VOLT_OVP_9p5V (5 << BQ2425X_VOLT_OVP_SHIFT) /* 9.5V */
# define BQ2425X_VOLT_OVP_10p0V (6 << BQ2425X_VOLT_OVP_SHIFT) /* 10.0V */
# define BQ2425X_VOLT_OVP_10p5V (7 << BQ2425X_VOLT_OVP_SHIFT) /* 10.5V */
#define BQ2425X_CLR_VDP (1 << 4) /* 0 = Keep D+ voltage ; 1 = Turn off D+ voltage */
#define BQ2425X_FORCE_BAT_DET (1 << 3) /* Enter the battery detection routine */
#define BQ2425X_FORCE_PTM (1 << 2) /* PTM mode enable */
/* bit 1: reserved */
/* bit 0: reserved */
#endif /* __DRIVERS_POWER_BQ2425X_H */

View file

@ -219,7 +219,7 @@ int battery_charger_register(FAR const char *devpath,
#if defined(CONFIG_I2C) && defined(CONFIG_I2C_BQ2425X)
struct i2c_dev_s; /* Forward reference */
FAR struct battery_charger_dev_s *bq2425x_initialize(FAR struct i2c_dev_s *i2c
FAR struct battery_charger_dev_s *bq2425x_initialize(FAR struct i2c_dev_s *i2c,
uint8_t addr,
uint32_t frequency);
#endif