mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-02 13:27:32 +08:00
Refactor battery monitor to use asynchronous i2c API (as does regular paparazzi) (#2082)
This commit is contained in:
committed by
GitHub
parent
8806e853f3
commit
28c343468d
@@ -32,7 +32,6 @@
|
|||||||
<message name="BATTERY_MONITOR" period="1.0"/>
|
<message name="BATTERY_MONITOR" period="1.0"/>
|
||||||
|
|
||||||
<message name="GPS_LLA" period="1.0"/>
|
<message name="GPS_LLA" period="1.0"/>
|
||||||
<message name="MOTOR_MIXING" period="1.0"/>
|
|
||||||
<message name="ATTITUDE" period="1.0"/>
|
<message name="ATTITUDE" period="1.0"/>
|
||||||
</mode>
|
</mode>
|
||||||
|
|
||||||
|
|||||||
@@ -110,7 +110,7 @@ void battery_monitor_init_bus(void){
|
|||||||
// transactions
|
// transactions
|
||||||
batmonbus.bus_trans.status = I2CTransDone;
|
batmonbus.bus_trans.status = I2CTransDone;
|
||||||
batmonbus.addr = BATTERY_MONITOR_BUS_ADC_I2C_ADDR;
|
batmonbus.addr = BATTERY_MONITOR_BUS_ADC_I2C_ADDR;
|
||||||
batmonbus.bus_status = BATTERY_MONITOR_BUS_CURRENT; // device status
|
batmonbus.bus_status = BATTERY_MONITOR_BUS_CURRENT_REQ; // device status
|
||||||
// Current readings
|
// Current readings
|
||||||
batmonbus.bus_current_mvolts = 0; // mV
|
batmonbus.bus_current_mvolts = 0; // mV
|
||||||
batmonbus.bus_current = 0; // A
|
batmonbus.bus_current = 0; // A
|
||||||
@@ -125,7 +125,7 @@ void battery_monitor_init_bus(void){
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Initalizes balance ADC 1
|
* Initalizes balance ADC
|
||||||
*/
|
*/
|
||||||
void battery_monitor_init_balance(struct BatMonBal* batmonbal){
|
void battery_monitor_init_balance(struct BatMonBal* batmonbal){
|
||||||
batmonbal->bus_trans.status = I2CTransDone;
|
batmonbal->bus_trans.status = I2CTransDone;
|
||||||
@@ -156,9 +156,39 @@ void battery_monitor_init(void) {
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* Event function
|
* Event function
|
||||||
|
* Check i2c transaction status for each device
|
||||||
*/
|
*/
|
||||||
void battery_monitor_event(void){
|
void battery_monitor_event(void){
|
||||||
// Empty for now
|
battery_monitor_check_i2c_transaction(&batmonbal1.bus_trans);
|
||||||
|
battery_monitor_check_i2c_transaction(&batmonbal2.bus_trans);
|
||||||
|
battery_monitor_check_i2c_transaction(&batmonbus.bus_trans);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Complete i2c transactions once they succeed or fail
|
||||||
|
*/
|
||||||
|
void battery_monitor_check_i2c_transaction(struct i2c_transaction* t){
|
||||||
|
switch (t->status) {
|
||||||
|
case I2CTransPending:
|
||||||
|
// wait and do nothing
|
||||||
|
break;
|
||||||
|
case I2CTransRunning:
|
||||||
|
// wait and do nothing
|
||||||
|
break;
|
||||||
|
case I2CTransSuccess:
|
||||||
|
// set to done
|
||||||
|
t->status = I2CTransDone;
|
||||||
|
break;
|
||||||
|
case I2CTransFailed:
|
||||||
|
// set to done
|
||||||
|
t->status = I2CTransDone;
|
||||||
|
break;
|
||||||
|
case I2CTransDone:
|
||||||
|
// do nothing
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -168,16 +198,23 @@ void battery_monitor_read_bus(void){
|
|||||||
batmonbus.data = 0; // erase at each iteration
|
batmonbus.data = 0; // erase at each iteration
|
||||||
|
|
||||||
switch (batmonbus.bus_status) {
|
switch (batmonbus.bus_status) {
|
||||||
case BATTERY_MONITOR_BUS_CURRENT:
|
// reqtest BUS_CURRENT measurement
|
||||||
|
case BATTERY_MONITOR_BUS_CURRENT_REQ:
|
||||||
// set ADC to current channel
|
// set ADC to current channel
|
||||||
batmonbus.bus_trans.buf[0] = battery_monitor_get_address(
|
batmonbus.bus_trans.buf[0] = battery_monitor_get_address(
|
||||||
(uint8_t)BATTERY_MONITOR_BUS_CURRENT_CHANNEL);
|
(uint8_t)BATTERY_MONITOR_BUS_CURRENT_CHANNEL);
|
||||||
//set to zero so we can detect an error
|
//set to zero so we can detect an error
|
||||||
batmonbus.bus_current = 0;
|
batmonbus.bus_current = 0;
|
||||||
// blocking transaction
|
|
||||||
|
// non-blocking transaction
|
||||||
if (i2c_transceive(&BATTERY_MONITOR_I2C_DEV, &batmonbus.bus_trans, batmonbus.addr, 1, 2)){
|
if (i2c_transceive(&BATTERY_MONITOR_I2C_DEV, &batmonbus.bus_trans, batmonbus.addr, 1, 2)){
|
||||||
// proceed only if transaction was submitted successfully
|
batmonbus.bus_status = BATTERY_MONITOR_BUS_CURRENT_READ;
|
||||||
if (batmonbus.bus_trans.status == I2CTransSuccess) {
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
// read BUS_CURRENT data
|
||||||
|
case BATTERY_MONITOR_BUS_CURRENT_READ:
|
||||||
|
if (batmonbus.bus_trans.status == I2CTransDone) {
|
||||||
// read data
|
// read data
|
||||||
batmonbus.data = (uint16_t) (batmonbus.bus_trans.buf[0] << 8 | batmonbus.bus_trans.buf[1]);
|
batmonbus.data = (uint16_t) (batmonbus.bus_trans.buf[0] << 8 | batmonbus.bus_trans.buf[1]);
|
||||||
// NOTE: we are not using the ALERT_FLAG at the moment,
|
// NOTE: we are not using the ALERT_FLAG at the moment,
|
||||||
@@ -193,27 +230,31 @@ void battery_monitor_read_bus(void){
|
|||||||
// convert to [A]
|
// convert to [A]
|
||||||
batmonbus.bus_current = ((float)batmonbus.bus_current_mvolts +
|
batmonbus.bus_current = ((float)batmonbus.bus_current_mvolts +
|
||||||
(float)batmon_current_offset) / batmon_current_sensitivity;
|
(float)batmon_current_offset) / batmon_current_sensitivity;
|
||||||
}
|
|
||||||
// optional: check for errors and reset i2c transaction
|
|
||||||
// shouldn't be needed
|
|
||||||
|
|
||||||
// update status
|
|
||||||
batmonbus.bus_status = BATTERY_MONITOR_BUS_VOLTAGE;
|
|
||||||
}
|
|
||||||
//update electrical subsystem, current in mAs
|
//update electrical subsystem, current in mAs
|
||||||
electrical.current = (int32_t)(batmonbus.bus_current*1000);
|
electrical.current = (int32_t)(batmonbus.bus_current*1000);
|
||||||
|
|
||||||
|
// increment status
|
||||||
|
batmonbus.bus_status = BATTERY_MONITOR_BUS_VOLTAGE_REQ;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BATTERY_MONITOR_BUS_VOLTAGE:
|
// request voltage data
|
||||||
|
case BATTERY_MONITOR_BUS_VOLTAGE_REQ:
|
||||||
// set ADC to voltage channel
|
// set ADC to voltage channel
|
||||||
batmonbus.bus_trans.buf[0] = battery_monitor_get_address(
|
batmonbus.bus_trans.buf[0] = battery_monitor_get_address(
|
||||||
(uint8_t)BATTERY_MONITOR_BUS_VOLTAGE_CHANNEL);
|
(uint8_t)BATTERY_MONITOR_BUS_VOLTAGE_CHANNEL);
|
||||||
//set to zero so we can detect an error
|
//set to zero so we can detect an error
|
||||||
batmonbus.bus_voltage_mvolts = 0;
|
batmonbus.bus_voltage_mvolts = 0;
|
||||||
// blocking transaction
|
|
||||||
|
// non-blocking transaction
|
||||||
if (i2c_transceive(&BATTERY_MONITOR_I2C_DEV, &batmonbus.bus_trans, batmonbus.addr, 1, 2)){
|
if (i2c_transceive(&BATTERY_MONITOR_I2C_DEV, &batmonbus.bus_trans, batmonbus.addr, 1, 2)){
|
||||||
// proceed only if transaction was submitted successfully
|
batmonbus.bus_status = BATTERY_MONITOR_BUS_VOLTAGE_READ;
|
||||||
if (batmonbus.bus_trans.status == I2CTransSuccess) {
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
// read voltage data
|
||||||
|
case BATTERY_MONITOR_BUS_VOLTAGE_READ:
|
||||||
|
if (batmonbus.bus_trans.status == I2CTransDone) {
|
||||||
// read data
|
// read data
|
||||||
batmonbus.data = (uint16_t) (batmonbus.bus_trans.buf[0] << 8 | batmonbus.bus_trans.buf[1]);
|
batmonbus.data = (uint16_t) (batmonbus.bus_trans.buf[0] << 8 | batmonbus.bus_trans.buf[1]);
|
||||||
// NOTE: we are not using the ALERT_FLAG at the moment,
|
// NOTE: we are not using the ALERT_FLAG at the moment,
|
||||||
@@ -229,13 +270,6 @@ void battery_monitor_read_bus(void){
|
|||||||
// convert to actual voltage
|
// convert to actual voltage
|
||||||
batmonbus.bus_voltage_mvolts = (uint16_t)(
|
batmonbus.bus_voltage_mvolts = (uint16_t)(
|
||||||
(float)batmonbus.bus_voltage_mvolts * BatmonVbusGain);
|
(float)batmonbus.bus_voltage_mvolts * BatmonVbusGain);
|
||||||
}
|
|
||||||
// optional: check for errors and reset i2c transaction
|
|
||||||
// shouldn't be needed
|
|
||||||
|
|
||||||
// update status
|
|
||||||
batmonbus.bus_status = BATTERY_MONITOR_BUS_TEMPERATURE;
|
|
||||||
}
|
|
||||||
|
|
||||||
//update electrical subsystem, voltage in decivolts
|
//update electrical subsystem, voltage in decivolts
|
||||||
if (batmonbus.bus_voltage_mvolts != 0) {
|
if (batmonbus.bus_voltage_mvolts != 0) {
|
||||||
@@ -244,18 +278,29 @@ void battery_monitor_read_bus(void){
|
|||||||
else {
|
else {
|
||||||
electrical.vsupply = 0;
|
electrical.vsupply = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// update status
|
||||||
|
batmonbus.bus_status = BATTERY_MONITOR_BUS_TEMPERATURE_REQ;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BATTERY_MONITOR_BUS_TEMPERATURE:
|
// request temperature data
|
||||||
|
case BATTERY_MONITOR_BUS_TEMPERATURE_REQ:
|
||||||
// set ADC to correct temperature channel
|
// set ADC to correct temperature channel
|
||||||
batmonbus.bus_trans.buf[0] = battery_monitor_get_address(
|
batmonbus.bus_trans.buf[0] = battery_monitor_get_address(
|
||||||
battery_monitor_tempmap[batmonbus.t_idx]);
|
battery_monitor_tempmap[batmonbus.t_idx]);
|
||||||
//set to zero so we can detect an error
|
//set to zero so we can detect an error
|
||||||
batmonbus.bus_temp[batmonbus.t_idx] = 0;
|
batmonbus.bus_temp[batmonbus.t_idx] = 0;
|
||||||
// blocking transaction
|
|
||||||
|
// non-blocking transaction
|
||||||
if (i2c_transceive(&BATTERY_MONITOR_I2C_DEV, &batmonbus.bus_trans, batmonbus.addr, 1, 2)){
|
if (i2c_transceive(&BATTERY_MONITOR_I2C_DEV, &batmonbus.bus_trans, batmonbus.addr, 1, 2)){
|
||||||
// proceed only if transaction was submitted successfully
|
batmonbus.bus_status = BATTERY_MONITOR_BUS_TEMPERATURE_READ;
|
||||||
if (batmonbus.bus_trans.status == I2CTransSuccess) {
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
// read temperature data
|
||||||
|
case BATTERY_MONITOR_BUS_TEMPERATURE_READ:
|
||||||
|
if (batmonbus.bus_trans.status == I2CTransDone) {
|
||||||
// read data
|
// read data
|
||||||
batmonbus.data = (uint16_t) (batmonbus.bus_trans.buf[0] << 8 | batmonbus.bus_trans.buf[1]);
|
batmonbus.data = (uint16_t) (batmonbus.bus_trans.buf[0] << 8 | batmonbus.bus_trans.buf[1]);
|
||||||
// NOTE: we are not using the ALERT_FLAG at the moment,
|
// NOTE: we are not using the ALERT_FLAG at the moment,
|
||||||
@@ -273,21 +318,17 @@ void battery_monitor_read_bus(void){
|
|||||||
batmonbus.bus_temp[batmonbus.t_idx] =
|
batmonbus.bus_temp[batmonbus.t_idx] =
|
||||||
((float)batmonbus.bus_tempsensors_mvolts[batmonbus.t_idx] +
|
((float)batmonbus.bus_tempsensors_mvolts[batmonbus.t_idx] +
|
||||||
(float)batmon_temp_offset ) / batmon_temp_sensitivity;
|
(float)batmon_temp_offset ) / batmon_temp_sensitivity;
|
||||||
}
|
|
||||||
}
|
|
||||||
// optional: check for errors and reset i2c transaction
|
|
||||||
// shouldn't be needed
|
|
||||||
|
|
||||||
// increment counter
|
// increment counter
|
||||||
batmonbus.t_idx++;
|
batmonbus.t_idx++;
|
||||||
if (batmonbus.t_idx == TEMP_SENSORS_NB) {
|
if (batmonbus.t_idx == TEMP_SENSORS_NB) {
|
||||||
batmonbus.t_idx = 0;
|
batmonbus.t_idx = 0;
|
||||||
batmonbus.bus_status = BATTERY_MONITOR_BUS_CURRENT; // to loop through
|
batmonbus.bus_status = BATTERY_MONITOR_BUS_CURRENT_REQ; // to loop through
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
// a recovery in case of a glitch
|
// a recovery in case of a glitch
|
||||||
batmonbus.bus_status = BATTERY_MONITOR_BUS_CURRENT;
|
batmonbus.bus_status = BATTERY_MONITOR_BUS_CURRENT_REQ;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -311,24 +352,11 @@ void battery_monitor_read_balance_ports_2(void) {
|
|||||||
* Read balance ADC
|
* Read balance ADC
|
||||||
*/
|
*/
|
||||||
void battery_monitor_read_balance_ports(struct BatMonBal* batmonbal) {
|
void battery_monitor_read_balance_ports(struct BatMonBal* batmonbal) {
|
||||||
batmonbal->data = 0; // erase at each iteration
|
// non-blocking transaction
|
||||||
|
// if transaction is done, request another measurement
|
||||||
// set the right address into ADC
|
// NOTE: optionally add startup delay, but it shouldn't be necessary
|
||||||
// cell_index is the number of the cell we want to probe
|
if (batmonbal->bus_trans.status == I2CTransDone) {
|
||||||
// battery_monitor_cellmap1 contains the mapping of channels for given cell number
|
// read data first (worst case we get some zeros)
|
||||||
// i.e. Cell_1 (cell_idx = 0) has channel 2
|
|
||||||
// this gets translated into hexadecimal number representing the channel internally
|
|
||||||
batmonbal->bus_trans.buf[0] =
|
|
||||||
battery_monitor_get_address((uint8_t)battery_monitor_cellmap[batmonbal->cell_index]);
|
|
||||||
|
|
||||||
//set to zero so we can detect an error
|
|
||||||
batmonbal->bat_cell_mvolts[batmonbal->cell_index] = 0;
|
|
||||||
|
|
||||||
// blocking transaction
|
|
||||||
if (i2c_transceive(&BATTERY_MONITOR_I2C_DEV, &batmonbal->bus_trans, batmonbal->addr, 1, 2)){
|
|
||||||
// proceed only if transaction was submitted successfully
|
|
||||||
if (batmonbal->bus_trans.status == I2CTransSuccess) {
|
|
||||||
// read data
|
|
||||||
batmonbal->data = (uint16_t) (batmonbal->bus_trans.buf[0] << 8 | batmonbal->bus_trans.buf[1]);
|
batmonbal->data = (uint16_t) (batmonbal->bus_trans.buf[0] << 8 | batmonbal->bus_trans.buf[1]);
|
||||||
// NOTE: we are not using the ALERT_FLAG at the moment,
|
// NOTE: we are not using the ALERT_FLAG at the moment,
|
||||||
// get counts
|
// get counts
|
||||||
@@ -348,14 +376,28 @@ void battery_monitor_read_balance_ports(struct BatMonBal* batmonbal) {
|
|||||||
batmonbal->bat_cell_mvolts[batmonbal->cell_index] =
|
batmonbal->bat_cell_mvolts[batmonbal->cell_index] =
|
||||||
(uint16_t)((float)batmonbal->bat_cell_mvolts[batmonbal->cell_index] *
|
(uint16_t)((float)batmonbal->bat_cell_mvolts[batmonbal->cell_index] *
|
||||||
battery_monitor_cellgains[batmonbal->cell_index]);
|
battery_monitor_cellgains[batmonbal->cell_index]);
|
||||||
}
|
|
||||||
// optional: check for errors and reset i2c transaction
|
|
||||||
// shouldn't be needed
|
|
||||||
}
|
|
||||||
|
|
||||||
// increment counter
|
// increment counter
|
||||||
batmonbal->cell_index++;
|
batmonbal->cell_index++;
|
||||||
if (batmonbal->cell_index == BATTERY_CELLS_NB) {
|
if (batmonbal->cell_index == BATTERY_CELLS_NB) {
|
||||||
batmonbal->cell_index = 0;
|
batmonbal->cell_index = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// erase data
|
||||||
|
batmonbal->data = 0; // erase at each iteration
|
||||||
|
|
||||||
|
//set to zero so we can detect an error
|
||||||
|
batmonbal->bat_cell_mvolts[batmonbal->cell_index] = 0;
|
||||||
|
|
||||||
|
// set the right address into ADC
|
||||||
|
// cell_index is the number of the cell we want to probe
|
||||||
|
// battery_monitor_cellmap1 contains the mapping of channels for given cell number
|
||||||
|
// i.e. Cell_1 (cell_idx = 0) has channel 2
|
||||||
|
// this gets translated into hexadecimal number representing the channel internally
|
||||||
|
batmonbal->bus_trans.buf[0] =
|
||||||
|
battery_monitor_get_address((uint8_t)battery_monitor_cellmap[batmonbal->cell_index]);
|
||||||
|
|
||||||
|
// request more data
|
||||||
|
i2c_transceive(&BATTERY_MONITOR_I2C_DEV, &batmonbal->bus_trans, batmonbal->addr, 1, 2);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -195,9 +195,12 @@ extern float batmon_temp_sensitivity;
|
|||||||
* Status for Bus ADC
|
* Status for Bus ADC
|
||||||
*/
|
*/
|
||||||
enum BatmonBusStatus {
|
enum BatmonBusStatus {
|
||||||
BATTERY_MONITOR_BUS_CURRENT,
|
BATTERY_MONITOR_BUS_CURRENT_REQ,
|
||||||
BATTERY_MONITOR_BUS_VOLTAGE,
|
BATTERY_MONITOR_BUS_CURRENT_READ,
|
||||||
BATTERY_MONITOR_BUS_TEMPERATURE
|
BATTERY_MONITOR_BUS_VOLTAGE_REQ,
|
||||||
|
BATTERY_MONITOR_BUS_VOLTAGE_READ,
|
||||||
|
BATTERY_MONITOR_BUS_TEMPERATURE_REQ,
|
||||||
|
BATTERY_MONITOR_BUS_TEMPERATURE_READ
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -255,6 +258,7 @@ void battery_monitor_read_balance_ports_2(void);
|
|||||||
void battery_monitor_read_balance_ports(struct BatMonBal *);
|
void battery_monitor_read_balance_ports(struct BatMonBal *);
|
||||||
|
|
||||||
void battery_monitor_event(void);
|
void battery_monitor_event(void);
|
||||||
|
void battery_monitor_check_i2c_transaction(struct i2c_transaction* t);
|
||||||
|
|
||||||
uint8_t battery_monitor_get_address(uint8_t channel);
|
uint8_t battery_monitor_get_address(uint8_t channel);
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user