FL-339: cli diagnostic interface for power subsystem. (#256)

* Core, API: add externs for c++
* Makefile: improve debug speed, flash with openocd, cleanup f2 config
* Power: add cli diagnostic.
* Local: fix api hal externs
* Local: fix externs in main and flipper_hal
* F2: power state dump stabs
* Bootloader flashing with openocd
* F3: move bq drivers to libs
* temporary do not build drivers on local
* temporary do not build drivers on f2

Co-authored-by: aanper <mail@s3f.ru>
This commit is contained in:
あく 2020-12-02 13:47:13 +03:00 committed by GitHub
parent f58b322bb5
commit 3a6fbff8c3
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
31 changed files with 418 additions and 73 deletions

View File

@ -105,6 +105,22 @@ void power_cli_dfu(string_t args, void* context) {
NVIC_SystemReset();
}
void power_cli_test(string_t args, void* context) {
string_t buffer;
string_init(buffer);
api_hal_power_dump_state(buffer);
cli_print(string_get_cstr(buffer));
string_clear(buffer);
}
void power_cli_otg_on(string_t args, void* context) {
api_hal_power_enable_otg();
}
void power_cli_otg_off(string_t args, void* context) {
api_hal_power_disable_otg();
}
void power_task(void* p) {
(void)p;
Power* power = power_alloc();
@ -113,6 +129,9 @@ void power_task(void* p) {
cli_add_command(power->cli, "poweroff", power_cli_poweroff, power);
cli_add_command(power->cli, "reset", power_cli_reset, power);
cli_add_command(power->cli, "dfu", power_cli_dfu, power);
cli_add_command(power->cli, "power_test", power_cli_test, power);
cli_add_command(power->cli, "power_otg_on", power_cli_otg_on, power);
cli_add_command(power->cli, "power_otg_off", power_cli_otg_off, power);
}
FuriRecordSubscriber* gui_record = furi_open_deprecated("gui", false, false, NULL, NULL, NULL);

View File

@ -5,6 +5,7 @@ FW_ADDRESS = 0x08008000
OS_OFFSET = 0x00008000
FLASH_ADDRESS = 0x08000000
DEBUG_AGENT = openocd -f interface/stlink.cfg -c "transport select hla_swd" -f target/stm32l4x.cfg -c "init" -c "adapter speed 4000"
BOOT_CFLAGS = -DBOOT_ADDRESS=$(BOOT_ADDRESS) -DFW_ADDRESS=$(FW_ADDRESS) -DOS_OFFSET=$(OS_OFFSET)
MCU_FLAGS = -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard

View File

@ -5,6 +5,7 @@ FW_ADDRESS = 0x08008000
OS_OFFSET = 0x00008000
FLASH_ADDRESS = 0x08000000
DEBUG_AGENT = openocd -f interface/stlink.cfg -c "transport select hla_swd" -f target/stm32wbx.cfg -c "init" -c "adapter speed 4000"
BOOT_CFLAGS = -DBOOT_ADDRESS=$(BOOT_ADDRESS) -DFW_ADDRESS=$(FW_ADDRESS) -DOS_OFFSET=$(OS_OFFSET)
MCU_FLAGS = -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard

View File

@ -1,8 +1,8 @@
#include <stdio.h>
extern "C" {
#include "flipper.h"
#include "flipper_v2.h"
extern "C" {
#include "log.h"
#include "applications.h"
#include "tty_uart.h"

View File

@ -1,23 +1,24 @@
#pragma once
#include "api-hal.h"
#ifdef __cplusplus
extern "C" {
#endif
#include "main.h"
#include "api-hal.h"
#include "cmsis_os.h"
#include "furi-deprecated.h"
#include "log.h"
#include "input/input.h"
#ifdef __cplusplus
}
#endif
#include <stdio.h>
void set_exitcode(uint32_t _exitcode);
#define FURI_LIB (const char*[])
#ifdef __cplusplus
}
#endif

View File

@ -1,8 +1,16 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
typedef enum {
ApiHalBootModeNormal,
ApiHalBootModeDFU
} ApiHalBootMode;
void api_hal_boot_set_mode(ApiHalBootMode mode);
#ifdef __cplusplus
}
#endif

View File

@ -1,6 +1,14 @@
#pragma once
#include "main.h"
#ifdef __cplusplus
extern "C" {
#endif
void delay(float milliseconds);
void delay_us(float microseconds);
void delay_us_init_DWT(void);
#ifdef __cplusplus
}
#endif

View File

@ -2,6 +2,11 @@
#include <stdint.h>
#include <stdbool.h>
#include <m-string.h>
#ifdef __cplusplus
extern "C" {
#endif
/* Initialize drivers */
void api_hal_power_init();
@ -20,3 +25,16 @@ void api_hal_power_enable_otg();
/* OTG disable */
void api_hal_power_disable_otg();
/* Get battery voltage in V */
float api_hal_power_get_battery_voltage();
/* Get battery current in A */
float api_hal_power_get_battery_current();
/* Get power system component state */
void api_hal_power_dump_state(string_t buffer);
#ifdef __cplusplus
}
#endif

View File

@ -3,8 +3,16 @@
#include <stdint.h>
#include <stddef.h>
#ifdef __cplusplus
extern "C" {
#endif
/* Get platform UID size in bytes */
size_t api_hal_uid_size();
/* Get const pointer to UID */
const uint8_t* api_hal_uid();
#ifdef __cplusplus
}
#endif

View File

@ -4,6 +4,10 @@
#include <stdint.h>
#include <string.h>
#ifdef __cplusplus
extern "C" {
#endif
/* Init VCP HAL
* Allocates ring buffer and initializes state
*/
@ -22,3 +26,7 @@ size_t api_hal_vcp_rx(uint8_t* buffer, size_t size);
* @param size - buffer size
*/
void api_hal_vcp_tx(uint8_t* buffer, size_t size);
#ifdef __cplusplus
}
#endif

View File

@ -1,5 +1,9 @@
#pragma once
#ifdef __cplusplus
template <unsigned int N> struct STOP_EXTERNING_ME {};
#endif
#include "api-hal-boot.h"
#include "api-hal-gpio.h"
#include "api-hal-delay.h"

View File

@ -2,6 +2,10 @@
#include "main.h"
#include "stdbool.h"
#ifdef __cplusplus
extern "C" {
#endif
// this defined in xx_hal_gpio.c, so...
#define GPIO_NUMBER (16U)
@ -67,3 +71,7 @@ static inline bool hal_gpio_read(const GpioPin* gpio) {
bool hal_gpio_read_sd_detect(void);
void enable_cc1101_irq();
#ifdef __cplusplus
}
#endif

View File

@ -1,20 +1,20 @@
#include <api-hal-power.h>
#include <adc.h>
#include <math.h>
#define BATTERY_MIN_VOLTAGE 3.2f
#define BATTERY_MAX_VOLTAGE 4.0f
#define BATTERY_MIN_VOLTAGE 3.4f
#define BATTERY_MAX_VOLTAGE 4.1f
void api_hal_power_init() {}
uint8_t api_hal_power_get_pct() {
float value;
HAL_ADC_Start(&hadc1);
if(HAL_ADC_PollForConversion(&hadc1, 1000) != HAL_TIMEOUT) {
value = HAL_ADC_GetValue(&hadc1);
float value = api_hal_power_get_battery_voltage();
if (value == NAN || value < BATTERY_MIN_VOLTAGE) {
return 0;
}
value = ((float)value / 10 * 2 - BATTERY_MIN_VOLTAGE) /
(BATTERY_MAX_VOLTAGE - BATTERY_MIN_VOLTAGE);
value = (value - BATTERY_MIN_VOLTAGE) / (BATTERY_MAX_VOLTAGE - BATTERY_MIN_VOLTAGE) * 100;
if(value > 100) {
value = 100;
@ -32,3 +32,33 @@ void api_hal_power_off() {}
void api_hal_power_enable_otg() {}
void api_hal_power_disable_otg() {}
float api_hal_power_get_battery_voltage() {
ADC_ChannelConfTypeDef sConfig = {0};
sConfig.Channel = ADC_CHANNEL_4;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) {
Error_Handler();
}
float value = NAN;
HAL_ADC_Start(&hadc1);
if(HAL_ADC_PollForConversion(&hadc1, 1000) != HAL_TIMEOUT) {
// adc range / 12 bits * adc_value * divider ratio * sampling drag correction
value = 3.3f / 4096.0f * HAL_ADC_GetValue(&hadc1) * 2 * 1.3;
}
return value;
}
float api_hal_power_get_battery_current() {
return NAN;
}
void api_hal_power_dump_state(string_t buffer) {
string_cat_printf(buffer, "Not supported");
}

View File

@ -1,6 +1,6 @@
TOOLCHAIN = arm
DEBUG_AGENT = openocd -f interface/stlink-v2.cfg -c "transport select hla_swd" -f target/stm32l4x.cfg -c "init"
DEBUG_AGENT = openocd -f interface/stlink.cfg -c "transport select hla_swd" -f target/stm32l4x.cfg -c "init" -c "adapter speed 4000"
BOOT_ADDRESS = 0x08000000
FW_ADDRESS = 0x08008000

View File

@ -1,18 +0,0 @@
#pragma once
#include <stdbool.h>
/* Initialize Driver */
void bq25896_init();
/* Send device into shipping mode */
void bq25896_poweroff();
/* Is currently charging */
bool bq25896_is_charging();
/* Enable otg */
void bq25896_enable_otg();
/* Disable otg */
void bq25896_disable_otg();

View File

@ -1,21 +0,0 @@
#pragma once
#include <stdint.h>
/* Initialize Driver */
void bq27220_init();
/* Get battery voltage in mV */
uint16_t bq27220_get_voltage();
/* Get current in mA */
int16_t bq27220_get_current();
/* Get compensated full charge capacity in in mAh */
uint16_t bq27220_get_full_charge_capacity();
/* Get remaining capacity in in mAh */
uint16_t bq27220_get_remaining_capacity();
/* Get predicted remaining battery capacity in percents */
uint16_t bq27220_get_state_of_charge();

View File

@ -2,6 +2,10 @@
#include "main.h"
#include "stdbool.h"
#ifdef __cplusplus
extern "C" {
#endif
// this defined in xx_hal_gpio.c, so...
#define GPIO_NUMBER (16U)
@ -67,3 +71,7 @@ static inline bool hal_gpio_read(const GpioPin* gpio) {
bool hal_gpio_read_sd_detect(void);
void enable_cc1101_irq();
#ifdef __cplusplus
}
#endif

View File

@ -26,3 +26,58 @@ void api_hal_power_enable_otg() {
void api_hal_power_disable_otg() {
bq25896_disable_otg();
}
float api_hal_power_get_battery_voltage() {
return (float)bq27220_get_voltage() / 1000.0f;
}
float api_hal_power_get_battery_current() {
return (float)bq27220_get_current() / 1000.0f;
}
void api_hal_power_dump_state(string_t buffer) {
BatteryStatus battery_status;
OperationStatus operation_status;
if (bq27220_get_battery_status(&battery_status) == BQ27220_ERROR
|| bq27220_get_operation_status(&operation_status) == BQ27220_ERROR) {
string_cat_printf(buffer, "Failed to get bq27220 status. Communication error.\r\n");
} else {
string_cat_printf(buffer,
"bq27220: CALMD: %d, SEC0: %d, SEC1: %d, EDV2: %d, VDQ: %d, INITCOMP: %d, SMTH: %d, BTPINT: %d, CFGUPDATE: %d\r\n",
operation_status.CALMD, operation_status.SEC0, operation_status.SEC1,
operation_status.EDV2, operation_status.VDQ, operation_status.INITCOMP,
operation_status.SMTH, operation_status.BTPINT, operation_status.CFGUPDATE
);
// Battery status register, part 1
string_cat_printf(buffer,
"bq27220: CHGINH: %d, FC: %d, OTD: %d, OTC: %d, SLEEP: %d, OCVFAIL: %d, OCVCOMP: %d, FD: %d\r\n",
battery_status.CHGINH, battery_status.FC, battery_status.OTD,
battery_status.OTC, battery_status.SLEEP, battery_status.OCVFAIL,
battery_status.OCVCOMP, battery_status.FD
);
// Battery status register, part 2
string_cat_printf(buffer,
"bq27220: DSG: %d, SYSDWN: %d, TDA: %d, BATTPRES: %d, AUTH_GD: %d, OCVGD: %d, TCA: %d, RSVD: %d\r\n",
battery_status.DSG, battery_status.SYSDWN, battery_status.TDA,
battery_status.BATTPRES, battery_status.AUTH_GD, battery_status.OCVGD,
battery_status.TCA, battery_status.RSVD
);
// Voltage and current info
string_cat_printf(buffer,
"bq27220: Full capacity: %dmAh, Remaining capacity: %dmAh, State of Charge: %d%%\r\n",
bq27220_get_full_charge_capacity(), bq27220_get_remaining_capacity(),
bq27220_get_state_of_charge()
);
string_cat_printf(buffer,
"bq27220: Voltage: %dmV, Current: %dmA, Temperature: %dC\r\n",
bq27220_get_voltage(), bq27220_get_current(), (bq27220_get_temperature() - 2731)/10
);
}
string_cat_printf(buffer,
"bq25896: VBUS: %d, VSYS: %d, VBAT: %d, Current: %d, NTC: %dm%%\r\n",
bq25896_get_vbus_voltage(), bq25896_get_vsys_voltage(),
bq25896_get_vbat_voltage(), bq25896_get_vbat_current(),
bq25896_get_ntc_mpct()
);
}

View File

@ -1,6 +1,6 @@
TOOLCHAIN = arm
DEBUG_AGENT = openocd -f interface/stlink.cfg -c "transport select hla_swd" -f target/stm32wbx.cfg -c "init"
DEBUG_AGENT = openocd -f interface/stlink.cfg -c "transport select hla_swd" -f target/stm32wbx.cfg -c "init" -c "adapter speed 4000"
BOOT_ADDRESS = 0x08000000
FW_ADDRESS = 0x08008000

View File

@ -10,6 +10,10 @@ GPIO and HAL implementations
#include <stdbool.h>
#include "main.h"
#ifdef __cplusplus
extern "C" {
#endif
#define GPIOA "PA"
#define GPIOB "PB"
#define GPIOC "PC"
@ -50,4 +54,8 @@ typedef const char* SPI_HandleTypeDef;
typedef uint32_t HAL_StatusTypeDef;
HAL_StatusTypeDef
HAL_SPI_Transmit(SPI_HandleTypeDef* hspi, uint8_t* pData, uint16_t Size, uint32_t Timeout);
HAL_SPI_Transmit(SPI_HandleTypeDef* hspi, uint8_t* pData, uint16_t Size, uint32_t Timeout);
#ifdef __cplusplus
}
#endif

View File

@ -2,6 +2,10 @@
#include <stdlib.h>
#include <limits.h>
#ifdef __cplusplus
extern "C" {
#endif
#define HAL_MAX_DELAY INT_MAX
typedef uint32_t UART_HandleTypeDef;
@ -16,3 +20,7 @@ typedef uint32_t TIM_HandleTypeDef;
#define LED_GREEN_GPIO_Port "Green:"
#define LED_BLUE_Pin 1
#define LED_BLUE_GPIO_Port "Blue:"
#ifdef __cplusplus
}
#endif

View File

@ -2,6 +2,10 @@
#include "main.h"
#include "stdbool.h"
#ifdef __cplusplus
extern "C" {
#endif
// hw-api
typedef char GPIO_TypeDef;
@ -53,3 +57,7 @@ void hal_gpio_write(const GpioPin* gpio, const bool state);
bool hal_gpio_read(const GpioPin* gpio);
void enable_cc1101_irq();
#ifdef __cplusplus
}
#endif

View File

@ -3,6 +3,10 @@
#include <cmsis_os.h>
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
// Task stack size in bytes
#define DEFAULT_STACK_SIZE 4096
@ -12,3 +16,7 @@
bool task_equal(TaskHandle_t a, TaskHandle_t b);
bool task_is_isr_context(void);
__attribute__((unused)) void taskDISABLE_INTERRUPTS(void);
#ifdef __cplusplus
}
#endif

View File

@ -69,9 +69,6 @@ void bq25896_init() {
bq25896_regs.r14.REG_RST = 1;
bq25896_write_reg(0x14, (uint8_t*)&bq25896_regs.r14);
// bq25896_regs.r07.WATCHDOG = 0b00;
// bq25896_write_reg(0x07, (uint8_t*)&bq25896_regs.r07);
bq25896_read(0x00, (uint8_t*)&bq25896_regs, sizeof(bq25896_regs));
}
@ -81,19 +78,58 @@ void bq25896_poweroff() {
}
bool bq25896_is_charging() {
bq25896_regs.r03.WD_RST = 1;
bq25896_write_reg(0x03, (uint8_t*)&bq25896_regs.r03);
bq25896_read_reg(0x0B, (uint8_t*)&bq25896_regs.r0B);
return bq25896_regs.r0B.CHRG_STAT != ChrgStatNo;
}
void bq25896_enable_otg() {
bq25896_regs.r03.OTG_CONFIG = 1;
bq25896_write_reg(0x09, (uint8_t*)&bq25896_regs.r03);
bq25896_write_reg(0x03, (uint8_t*)&bq25896_regs.r03);
}
void bq25896_disable_otg() {
bq25896_regs.r03.OTG_CONFIG = 0;
bq25896_write_reg(0x09, (uint8_t*)&bq25896_regs.r03);
bq25896_write_reg(0x03, (uint8_t*)&bq25896_regs.r03);
}
void bq25896_adc_sample() {
bq25896_regs.r02.CONV_START = 1;
bq25896_write_reg(0x02, (uint8_t*)&bq25896_regs.r02);
while(bq25896_regs.r02.CONV_START == 1) {
bq25896_read_reg(0x02, (uint8_t*)&bq25896_regs.r02);
}
}
uint16_t bq25896_get_vbus_voltage() {
bq25896_adc_sample();
bq25896_read_reg(0x11, (uint8_t*)&bq25896_regs.r11);
if (bq25896_regs.r11.VBUS_GD) {
return (uint16_t)bq25896_regs.r11.VBUSV * 100 + 2600;
} else {
return 0;
}
}
uint16_t bq25896_get_vsys_voltage() {
bq25896_adc_sample();
bq25896_read_reg(0x0F, (uint8_t*)&bq25896_regs.r0F);
return (uint16_t)bq25896_regs.r0F.SYSV * 20 + 2304;
}
uint16_t bq25896_get_vbat_voltage() {
bq25896_adc_sample();
bq25896_read_reg(0x0E, (uint8_t*)&bq25896_regs.r0E);
return (uint16_t)bq25896_regs.r0E.BATV * 20 + 2304;
}
uint16_t bq25896_get_vbat_current() {
bq25896_adc_sample();
bq25896_read_reg(0x12, (uint8_t*)&bq25896_regs.r12);
return (uint16_t)bq25896_regs.r12.ICHGR * 50;
}
uint32_t bq25896_get_ntc_mpct() {
bq25896_adc_sample();
bq25896_read_reg(0x10, (uint8_t*)&bq25896_regs.r10);
return (uint32_t)bq25896_regs.r10.TSPCT * 465+21000;
}

34
lib/drivers/bq25896.h Normal file
View File

@ -0,0 +1,34 @@
#pragma once
#include <stdbool.h>
#include <stdint.h>
/* Initialize Driver */
void bq25896_init();
/* Send device into shipping mode */
void bq25896_poweroff();
/* Is currently charging */
bool bq25896_is_charging();
/* Enable otg */
void bq25896_enable_otg();
/* Disable otg */
void bq25896_disable_otg();
/* Get VBUS Voltage in mV */
uint16_t bq25896_get_vbus_voltage();
/* Get VSYS Voltage in mV */
uint16_t bq25896_get_vsys_voltage();
/* Get VBAT Voltage in mV */
uint16_t bq25896_get_vbat_voltage();
/* Get VBAT current in mA */
uint16_t bq25896_get_vbat_current();
/* Get NTC voltage in mpct of REGN */
uint32_t bq25896_get_ntc_mpct();

View File

@ -6,17 +6,18 @@
uint16_t bq27220_read_word(uint8_t address) {
uint8_t data[2] = { address };
if (HAL_I2C_Master_Transmit(&POWER_I2C, BQ27220_ADDRESS, data, 1, 2000) != HAL_OK) {
return 0;
return BQ27220_ERROR;
}
if (HAL_I2C_Master_Receive(&POWER_I2C, BQ27220_ADDRESS, data, 2, 2000) != HAL_OK) {
return 0;
return BQ27220_ERROR;
}
return *(uint16_t*)data;
}
bool bq27220_control(uint16_t control) {
uint8_t data[3] = { CommandControl };
uint8_t data[3];
data[0] = CommandControl;
data[1] = (control>>8) & 0xFF;
data[2] = control & 0xFF;
if (HAL_I2C_Master_Transmit(&POWER_I2C, BQ27220_ADDRESS, data, 3, 2000) != HAL_OK) {
@ -37,7 +38,31 @@ uint16_t bq27220_get_voltage() {
}
int16_t bq27220_get_current() {
return (int16_t)bq27220_read_word(CommandCurrent);
return bq27220_read_word(CommandCurrent);
}
uint8_t bq27220_get_battery_status(BatteryStatus* battery_status) {
uint16_t data = bq27220_read_word(CommandBatteryStatus);
if (data == BQ27220_ERROR) {
return BQ27220_ERROR;
} else {
*(uint16_t*)battery_status = data;
return BQ27220_SUCCESS;
}
}
uint8_t bq27220_get_operation_status(OperationStatus* operation_status) {
uint16_t data = bq27220_read_word(CommandOperationStatus);
if (data == BQ27220_ERROR) {
return BQ27220_ERROR;
} else {
*(uint16_t*)operation_status = data;
return BQ27220_SUCCESS;
}
}
uint16_t bq27220_get_temperature() {
return bq27220_read_word(CommandTemperature);
}
uint16_t bq27220_get_full_charge_capacity() {

71
lib/drivers/bq27220.h Normal file
View File

@ -0,0 +1,71 @@
#pragma once
#include <stdint.h>
#include <stdbool.h>
#define BQ27220_ERROR 0x0
#define BQ27220_SUCCESS 0x1
typedef struct {
// Low byte, Low bit first
bool DSG:1; // The device is in DISCHARGE
bool SYSDWN:1; // System down bit indicating the system should shut down
bool TDA:1; // Terminate Discharge Alarm
bool BATTPRES:1; // Battery Present detected
bool AUTH_GD:1; // Detect inserted battery
bool OCVGD:1; // Good OCV measurement taken
bool TCA:1; // Terminate Charge Alarm
bool RSVD:1; // Reserved
// High byte, Low bit first
bool CHGINH:1; // Charge inhibit
bool FC:1; // Full-charged is detected
bool OTD:1; // Overtemperature in discharge condition is detected
bool OTC:1; // Overtemperature in charge condition is detected
bool SLEEP:1; // Device is operating in SLEEP mode when set
bool OCVFAIL:1; // Status bit indicating that the OCV reading failed due to current
bool OCVCOMP:1; // An OCV measurement update is complete
bool FD:1; // Full-discharge is detected
} BatteryStatus;
typedef struct {
// Low byte, Low bit first
bool CALMD:1;
bool SEC0:1;
bool SEC1:1;
bool EDV2:1;
bool VDQ:1;
bool INITCOMP:1;
bool SMTH:1;
bool BTPINT:1;
// High byte, Low bit first
uint8_t RSVD1:2;
bool CFGUPDATE:1;
uint8_t RSVD0:5;
} OperationStatus;
/* Initialize Driver */
void bq27220_init();
/* Get battery voltage in mV or error */
uint16_t bq27220_get_voltage();
/* Get current in mA or error*/
int16_t bq27220_get_current();
/* Get battery status */
uint8_t bq27220_get_battery_status(BatteryStatus* battery_status);
/* Get operation status */
uint8_t bq27220_get_operation_status(OperationStatus* operation_status);
/* Get temperature in units of 0.1°K */
uint16_t bq27220_get_temperature();
/* Get compensated full charge capacity in in mAh */
uint16_t bq27220_get_full_charge_capacity();
/* Get remaining capacity in in mAh */
uint16_t bq27220_get_remaining_capacity();
/* Get predicted remaining battery capacity in percents */
uint16_t bq27220_get_state_of_charge();

View File

@ -68,4 +68,12 @@ CPP_SOURCES += $(wildcard $(ONEWIRE_DIR)/*.cpp)
CYFRAL_DIR = $(LIB_DIR)/cyfral
CFLAGS += -I$(CYFRAL_DIR)
CPP_SOURCES += $(wildcard $(CYFRAL_DIR)/*.cpp)
endif
endif
# drivers
ifneq ($(TARGET), local)
ifneq ($(TARGET), f2)
CFLAGS += -I$(LIB_DIR)/drivers
C_SOURCES += $(wildcard $(LIB_DIR)/drivers/*.c)
endif
endif

View File

@ -55,7 +55,7 @@ $(OBJ_DIR)/%.o: %.cpp $(OBJ_DIR)/BUILD_FLAGS $(ASSETS)
@$(CPP) $(CFLAGS) $(CPPFLAGS) -c $< -o $@
$(OBJ_DIR)/flash: $(OBJ_DIR)/$(PROJECT).bin
st-flash --reset write $(OBJ_DIR)/$(PROJECT).bin $(FLASH_ADDRESS)
$(DEBUG_AGENT) -c "program $(OBJ_DIR)/$(PROJECT).bin reset exit $(FLASH_ADDRESS)"
touch $@
$(OBJ_DIR)/upload: $(OBJ_DIR)/$(PROJECT).bin
@ -78,9 +78,10 @@ debug: flash
-ex "source ../debug/FreeRTOS/FreeRTOS.py" \
-ex "source ../debug/PyCortexMDebug/scripts/gdb.py" \
-ex "svd_load $(SVD_FILE)" \
-ex "compare-sections" \
$(OBJ_DIR)/$(PROJECT).elf; \
kill `cat $(OBJ_DIR)/agent.PID`; \
rm $(OBJ_DIR)/agent.PID
echo "reset; shutdown;" | nc 127.0.0.1 4444 > /dev/null
kill `cat $(OBJ_DIR)/agent.PID`; rm $(OBJ_DIR)/agent.PID > /dev/null
bm_debug: flash
set -m; blackmagic & echo $$! > $(OBJ_DIR)/agent.PID