Skip to content
Snippets Groups Projects
Commit a637366b authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Updated the battery firmware:

  - Added a bootloader.
  - Added the I2C communication with the battery.
  - Improved the capacity calculation.
Minor chnages to the driver class.
parent 4ac597b9
No related branches found
No related tags found
No related merge requests found
......@@ -6,32 +6,31 @@
#include "a2d.h"
short int battery_voltage;
short int input_current;
short int output_current;
float input_current;
float output_current;
// battery I2C slave address
unsigned char battery_id;
unsigned char EEMEM ee_battery_id=0x31;
// remaining_capacity
float remaining_capacity;
//float EEMEM ee_remaining_capacity=108000000.0;//mAs
float EEMEM ee_remaining_capacity=30000.0;//mAh
volatile unsigned short int remaining_capacity;
unsigned short int EEMEM ee_remaining_capacity=30000;//mAh
// maximum capacity
volatile float maximum_capacity;
//float EEMEM ee_maximum_capacity=108000000.0;//mAs
float EEMEM ee_maximum_capacity=30000.0;//mAh
volatile unsigned short int maximum_capacity;
unsigned short int EEMEM ee_maximum_capacity=30000;//mAh
// charge cycles
volatile short int charge_cycles;
short int EEMEM ee_charge_cycles=0;
volatile unsigned short int charge_cycles;
unsigned short int EEMEM ee_charge_cycles=0;
// accumutaed_capacity
float accumulated_capacity;
const float current_gain=48.828125;//mA
//const float period=0.001984*4;//s
const float period=0.000002204444;//h
const double current_gain=48.828125;//mA
const double period=0.00000222222;//h (8 ms)
void update_fuel_gauge(void)
{
float current_ma;
short int increment=0;
outb(TCNT0,131);// reload the timer value
// read the voltage and temperature from the battery
......@@ -39,26 +38,33 @@ void update_fuel_gauge(void)
input_current=adc_get_averaged_channel(6)*current_gain;
output_current=adc_get_averaged_channel(7)*current_gain;
// update the internal variables
remaining_capacity=remaining_capacity-(input_current*period);
accumulated_capacity+=(input_current-output_current)*period;
increment=(short int)accumulated_capacity;
accumulated_capacity-=increment;
remaining_capacity-=increment;
if(remaining_capacity>maximum_capacity)
remaining_capacity=maximum_capacity;
if(remaining_capacity<0)
remaining_capacity=0;
}
void fuel_gauge_init(void)
{
// read the data from the EEPROM
battery_id=eeprom_read_byte(&ee_battery_id);
remaining_capacity=eeprom_read_float(&ee_remaining_capacity);
maximum_capacity=eeprom_read_float(&ee_maximum_capacity);
remaining_capacity=eeprom_read_word(&ee_remaining_capacity);
maximum_capacity=eeprom_read_word(&ee_maximum_capacity);
charge_cycles=eeprom_read_word(&ee_charge_cycles);
accumulated_capacity=0.0;
// initialize the timer
timerInit();
timer0SetPrescaler(TIMER_CLK_DIV1024);
outb(TCNT0, 131);
outb(TCNT0,131);
timerAttach(TIMER0OVERFLOW_INT,update_fuel_gauge);
// attach timer functions
// initialize the i2c peripheral
i2cInit();
i2cSetBitrate(100);
// initialize the a2d converter
a2dInit();
a2dSetPrescaler(ADC_PRESCALE_DIV128);
......@@ -70,35 +76,66 @@ void fuel_gauge_init(void)
short int get_time_to_charged(void)
{
return ((maximum_capacity-remaining_capacity)*60)/output_current;
return ((maximum_capacity-remaining_capacity)*60.0)/output_current;
}
short int get_time_to_discharged(void)
{
return (remaining_capacity*60)/input_current;
return (remaining_capacity*60.0)/input_current;
}
short int get_input_current(void)
{
return input_current;
return (short int)input_current;
}
short int get_output_current(void)
{
return output_current;
return (short int)output_current;
}
short int get_voltage(void)
void get_voltage(unsigned char *voltage)
{
return 0;
unsigned char read_cmd,i;
unsigned char voltage_data[18];
// read the voltage registers of the battery
// send the read request
read_cmd=0x30;
if(i2cMasterSendNI(0x62,1,&read_cmd)==I2C_OK)
{
if(i2cMasterReceiveNI(0x62,18,voltage_data)==I2C_OK)
{
for(i=0;i<16;i++)
voltage[i]=voltage_data[i+2];
}
}
}
void get_temperature(unsigned char *temp1, unsigned char *temp2)
{
unsigned char temp_data[6];
unsigned char read_cmd;
read_cmd=0x4A;// device start read address
if(i2cMasterSendNI(0x62,1,&read_cmd)==I2C_OK)
{
if(i2cMasterReceiveNI(0x62,6,temp_data)==I2C_OK)
{
temp1[0]=temp_data[2];
temp1[1]=temp_data[3];
temp2[0]=temp_data[4];
temp2[1]=temp_data[5];
}
}
}
short int get_remaining_capacity(void)
{
return (short int)remaining_capacity;
return (short int)(remaining_capacity);
}
short int get_max_capacity(void)
{
return maximum_capacity;
return (short int)(maximum_capacity);
}
......@@ -6,7 +6,8 @@ short int get_time_to_charged(void);
short int get_time_to_discharged(void);
short int get_input_current(void);
short int get_output_current(void);
short int get_voltage(void);
void get_voltage(unsigned char *voltage);
void get_temperature(unsigned char *temp1, unsigned char *temp2);
short int get_remaining_capacity(void);
short int get_max_capacity(void);
......
......@@ -12,6 +12,7 @@ void InitGPIO(void)
// PC1 as an output (load_control)
DDRC=DDRC&0xF3;// PC2 as an input (UVP)
// Pc3 as an input (OVP)
PORTC=0x00;
}
......@@ -40,9 +41,9 @@ void handle_battery(void)
{
if(is_battery_present())
{
if(under_voltage_protection())
disable_battery();
else
// if(under_voltage_protection())
// disable_battery();
// else
enable_battery();
}
else
......@@ -53,15 +54,15 @@ void handle_load(void)
{
if(is_battery_present())
{
if(under_voltage_protection())
disable_load();
else
{
// if(under_voltage_protection())
// disable_load();
// else
// {
if(is_load_on())
enable_load();
else
disable_load();
}
// }
}
else
{
......
......@@ -234,7 +234,7 @@ u08 i2cMasterSendNI(u08 deviceAddr, u08 length, u08* data)
// transmit stop condition
// leave with TWEA on for slave receiving
i2cSendStop();
while( !(inb(TWCR) & BV(TWSTO)) );
while( !(inb(TWCR) & BV(TWEA)) );
// enable TWI interrupt
sbi(TWCR, TWIE);
......
......@@ -12,12 +12,14 @@
#include "fuel_gauge.h"
#include "i2c.h"
typedef struct
{
unsigned char header[2];
short int battery_voltage;
short int temperature1;
short int temperature2;
unsigned char battery_voltage[16];
unsigned char temperature1[2];
unsigned char temperature2[2];
unsigned char status;
// bit 0: battery_present
// bit 1: charger_present;
......@@ -33,11 +35,8 @@ typedef struct
int main (void)
{
// unsigned char read_cmd[2];
// unsigned char voltage_data[18];
// unsigned char temp_data[6];
unsigned char i;
TBatteryInfo info;
int i=0;
// initialize the GPIO
InitGPIO();
......@@ -53,74 +52,30 @@ int main (void)
info.header[1]=0xAA;
while(1)
{
// read the voltage registers of the battery
// send the read request
/* read_cmd[0]=0x30;// device start read address
read_cmd[1]=18;// read length
if(i2cMasterSendNI(0x60,2,read_cmd)==I2C_OK)
{
if(i2cMasterReceiveNI(0x60,18,voltage_data)==I2C_OK)
{
info.cell1_voltage[0]=voltage_data[2];
info.cell1_voltage[1]=voltage_data[3];
info.cell2_voltage[0]=voltage_data[4];
info.cell2_voltage[1]=voltage_data[5];
info.cell3_voltage[0]=voltage_data[6];
info.cell3_voltage[1]=voltage_data[7];
info.cell4_voltage[0]=voltage_data[8];
info.cell4_voltage[1]=voltage_data[9];
info.cell5_voltage[0]=voltage_data[10];
info.cell5_voltage[1]=voltage_data[11];
info.cell6_voltage[0]=voltage_data[12];
info.cell6_voltage[1]=voltage_data[13];
info.cell7_voltage[0]=voltage_data[14];
info.cell7_voltage[1]=voltage_data[15];
info.cell8_voltage[0]=voltage_data[16];
info.cell8_voltage[1]=voltage_data[17];
// read the voltage registers of the battery
// send the read request
read_cmd[0]=0x4A;// device start read address
read_cmd[1]=6;// read length
if(i2cMasterSendNI(0x60,2,read_cmd)==I2C_OK)
{
if(i2cMasterReceiveNI(0x60,6,temp_data)==I2C_OK)
{
info.temperature1[0]=temp_data[2];
info.temperature1[1]=temp_data[3];
info.temperature2[0]=temp_data[4];
info.temperature2[1]=temp_data[5];
info.battery_present=is_battery_present();
info.charger_present=is_charger_present();
info.load_on=is_load_on();
info.UVP=under_voltage_protection();
info.OVP=over_voltage_protection();
}
}
}
}*/
_delay_ms(1000);
handle_battery();
handle_load();
info.battery_voltage=get_voltage();
info.status=0x00;
if(is_battery_present())
info.status|=0x01;
if(is_charger_present())
info.status|=0x02;
if(is_load_on())
info.status|=0x04;
if(under_voltage_protection())
info.status|=0x08;
if(over_voltage_protection())
info.status|=0x10;
info.current_in=get_input_current();
info.current_out=get_output_current();
info.rem_capacity=get_remaining_capacity();
info.time_to_charged=get_time_to_charged();
info.time_to_discharged=get_time_to_discharged();
// send tha information packet
for(i=0;i<sizeof(TBatteryInfo);i++)
uartSendByte(((unsigned char *)&info)[i]);
_delay_ms(1000);
handle_battery();
handle_load();
get_voltage(info.battery_voltage);
get_temperature(info.temperature1,info.temperature2);
info.status=0x00;
if(is_battery_present())
info.status|=0x01;
if(is_charger_present())
info.status|=0x02;
if(is_load_on())
info.status|=0x04;
if(under_voltage_protection())
info.status|=0x08;
if(over_voltage_protection())
info.status|=0x10;
info.current_in=get_input_current();
info.current_out=get_output_current();
info.rem_capacity=get_remaining_capacity();
info.time_to_charged=get_time_to_charged();
info.time_to_discharged=get_time_to_discharged();
// send tha information packet
for(i=0;i<sizeof(TBatteryInfo);i++)
uartSendByte(((unsigned char *)&info)[i]);
}
}
......@@ -235,7 +235,7 @@ void timerPause(unsigned short pause_ms)
}
}
/* old inaccurate code, for reference
//old inaccurate code, for reference
// calculate delay for [pause_ms] milliseconds
u16 prescaleDiv = 1<<(pgm_read_byte(TimerPrescaleFactor+inb(TCCR0)));
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment