Import of the watch repository from Pebble

This commit is contained in:
Matthieu Jeanson 2024-12-12 16:43:03 -08:00 committed by Katharine Berry
commit 3b92768480
10334 changed files with 2564465 additions and 0 deletions

View file

@ -0,0 +1,97 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "drivers/button.h"
#include "board/board.h"
#include "drivers/periph_config.h"
#include "drivers/gpio.h"
static void initialize_button_common(void) {
if (!BOARD_CONFIG_BUTTON.button_com.gpio) {
// This board doesn't use a button common pin.
return;
}
// Configure BUTTON_COM to drive low. When the button
// is pressed this pin will be connected to the pin for the
// button.
gpio_use(BOARD_CONFIG_BUTTON.button_com.gpio);
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = BOARD_CONFIG_BUTTON.button_com.gpio_pin;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(BOARD_CONFIG_BUTTON.button_com.gpio, &GPIO_InitStructure);
GPIO_WriteBit(BOARD_CONFIG_BUTTON.button_com.gpio, BOARD_CONFIG_BUTTON.button_com.gpio_pin, 0);
gpio_release(BOARD_CONFIG_BUTTON.button_com.gpio);
}
static void initialize_button(const ButtonConfig* config) {
// Configure the pin itself
gpio_use(config->gpio);
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_PuPd = config->pull;
GPIO_InitStructure.GPIO_Pin = config->gpio_pin;
GPIO_Init(config->gpio, &GPIO_InitStructure);
gpio_release(config->gpio);
}
bool button_is_pressed(ButtonId id) {
const ButtonConfig* button_config = &BOARD_CONFIG_BUTTON.buttons[id];
gpio_use(button_config->gpio);
uint8_t bit = GPIO_ReadInputDataBit(button_config->gpio, button_config->gpio_pin);
gpio_release(button_config->gpio);
return !bit;
}
uint8_t button_get_state_bits(void) {
uint8_t button_state = 0x00;
for (int i = 0; i < NUM_BUTTONS; ++i) {
button_state |= (button_is_pressed(i) ? 0x01 : 0x00) << i;
}
return button_state;
}
void button_init(void) {
periph_config_acquire_lock();
periph_config_enable(RCC_APB2PeriphClockCmd, RCC_APB2Periph_SYSCFG);
initialize_button_common();
for (int i = 0; i < NUM_BUTTONS; ++i) {
initialize_button(&BOARD_CONFIG_BUTTON.buttons[i]);
}
periph_config_disable(RCC_APB2PeriphClockCmd, RCC_APB2Periph_SYSCFG);
periph_config_release_lock();
}
bool button_selftest(void) {
return button_get_state_bits() == 0;
}

View file

@ -0,0 +1,160 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "drivers/crc.h"
#include "drivers/flash.h"
#include "drivers/periph_config.h"
#include "system/passert.h"
#if defined(MICRO_FAMILY_STM32F2)
#include "stm32f2xx_crc.h"
#include "stm32f2xx_rcc.h"
#elif defined(MICRO_FAMILY_STM32F4)
#include "stm32f4xx_crc.h"
#include "stm32f4xx_rcc.h"
#endif
#include <inttypes.h>
static bool s_initialized = false;
static bool s_clock_running = false;
static void enable_crc_clock(void) {
// save the state so that if stop mode interrupts things, we resume cleanly
s_clock_running = true;
periph_config_enable(RCC_AHB1PeriphClockCmd, RCC_AHB1Periph_CRC);
}
static void disable_crc_clock(void) {
// save the state so that if stop mode interrupts things, we resume cleanly
s_clock_running = false;
periph_config_disable(RCC_AHB1PeriphClockCmd, RCC_AHB1Periph_CRC);
}
void crc_init(void) {
if (s_initialized) {
return;
}
s_initialized = true;
}
void crc_calculate_incremental_start(void) {
PBL_ASSERTN(s_initialized);
enable_crc_clock();
CRC_ResetDR();
}
static void crc_calculate_incremental_words(const uint32_t* data, unsigned int data_length) {
PBL_ASSERTN(s_initialized);
CRC_CalcBlockCRC((uint32_t*) data, data_length);
}
static uint32_t crc_calculate_incremental_remaining_bytes(const uint8_t* data, unsigned int data_length) {
PBL_ASSERTN(s_initialized);
uint32_t crc_value;
if (data_length >= 4) {
const unsigned int num_words = data_length / 4;
crc_calculate_incremental_words((uint32_t*) data, num_words);
data += num_words * 4;
data_length -= num_words * 4;
}
if (data_length) {
uint32_t last_word = 0;
for (unsigned int i = 0; i < data_length; ++i) {
last_word = (last_word << 8) | data[i];
}
crc_value = CRC_CalcCRC(last_word);
} else {
crc_value = CRC_GetCRC();
}
return crc_value;
}
void crc_calculate_incremental_stop(void) {
PBL_ASSERTN(s_initialized);
disable_crc_clock();
}
uint32_t crc_calculate_bytes(const uint8_t* data, unsigned int data_length) {
crc_calculate_incremental_start();
// First calculate the CRC of the whole words, since the hardware works 4
// bytes at a time.
uint32_t* data_words = (uint32_t*) data;
const unsigned int num_words = data_length / 4;
crc_calculate_incremental_words(data_words, num_words);
const unsigned int num_remaining_bytes = data_length % 4;
const uint32_t res = crc_calculate_incremental_remaining_bytes(data + (num_words * 4), num_remaining_bytes);
crc_calculate_incremental_stop();
return (res);
}
uint32_t crc_calculate_flash(uint32_t address, unsigned int num_bytes) {
crc_calculate_incremental_start();
const unsigned int chunk_size = 128;
uint8_t buffer[chunk_size];
while (num_bytes > chunk_size) {
flash_read_bytes(buffer, address, chunk_size);
crc_calculate_incremental_words((const uint32_t*) buffer, chunk_size / 4);
num_bytes -= chunk_size;
address += chunk_size;
}
flash_read_bytes(buffer, address, num_bytes);
const uint32_t res = crc_calculate_incremental_remaining_bytes(buffer, num_bytes);
crc_calculate_incremental_stop();
return (res);
}
uint8_t crc8_calculate_bytes(const uint8_t *data, unsigned int data_len) {
// Optimal polynomial chosen based on
// http://users.ece.cmu.edu/~koopman/roses/dsn04/koopman04_crc_poly_embedded.pdf
// Note that this is different than the standard CRC-8 polynomial, because the
// standard CRC-8 polynomial is not particularly good.
// nibble lookup table for (x^8 + x^5 + x^3 + x^2 + x + 1)
static const uint8_t lookup_table[] =
{ 0, 47, 94, 113, 188, 147, 226, 205, 87, 120, 9, 38, 235, 196,
181, 154 };
uint16_t crc = 0;
for (int i = data_len * 2; i > 0; i--) {
uint8_t nibble = data[(i - 1)/ 2];
if (i % 2 == 0) {
nibble >>= 4;
}
int index = nibble ^ (crc >> 4);
crc = lookup_table[index & 0xf] ^ (crc << 4);
}
return crc;
}

View file

@ -0,0 +1,206 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "drivers/dbgserial.h"
#include "drivers/periph_config.h"
#include "system/passert.h"
#include "drivers/gpio.h"
#if defined(MICRO_FAMILY_STM32F2)
#include "stm32f2xx_rcc.h"
#include "stm32f2xx_gpio.h"
#include "stm32f2xx_usart.h"
#elif defined(MICRO_FAMILY_STM32F4)
#include "stm32f4xx_rcc.h"
#include "stm32f4xx_gpio.h"
#include "stm32f4xx_usart.h"
#endif
#include "util/attributes.h"
#include "util/cobs.h"
#include "util/crc32.h"
#include "util/net.h"
#include "util/misc.h"
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#define MAX_MESSAGE (256)
#define FRAME_DELIMITER '\x55'
#define PULSE_TRANSPORT_PUSH (0x5021)
#define PULSE_PROTOCOL_LOGGING (0x0003)
static bool s_initialized;
static const int SERIAL_BAUD_RATE = 1000000;
typedef struct PACKED PulseFrame {
net16 protocol;
unsigned char information[];
} PulseFrame;
typedef struct PACKED PushPacket {
net16 protocol;
net16 length;
unsigned char information[];
} PushPacket;
static const unsigned char s_message_header[] = {
// Message type: text
1,
// Source filename
'B', 'O', 'O', 'T', 'L', 'O', 'A', 'D', 'E', 'R', 0, 0, 0, 0, 0, 0,
// Log level and task
'*', '*',
// Timestamp
0, 0, 0, 0, 0, 0, 0, 0,
// Line number
0, 0,
};
static size_t s_message_length = 0;
static unsigned char s_message_buffer[MAX_MESSAGE];
void dbgserial_init(void) {
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
periph_config_acquire_lock();
/* Enable GPIO and UART3 peripheral clocks */
gpio_use(GPIOC);
periph_config_enable(RCC_APB1PeriphClockCmd, RCC_APB1Periph_USART3);
//USART_OverSampling8Cmd(USART3, ENABLE);
/* Connect PXx to USARTx_Tx*/
GPIO_PinAFConfig(GPIOC, GPIO_PinSource10, GPIO_AF_USART3);
/* Connect PXx to USARTx_Rx*/
GPIO_PinAFConfig(GPIOC, GPIO_PinSource11, GPIO_AF_USART3);
/* Configure USART Tx as alternate function */
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
GPIO_Init(GPIOC, &GPIO_InitStructure);
/* Configure USART Rx as alternate function */
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
GPIO_Init(GPIOC, &GPIO_InitStructure);
/* USART configuration */
USART_InitStructure.USART_BaudRate = SERIAL_BAUD_RATE;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(USART3, &USART_InitStructure);
/* Enable USART */
USART_Cmd(USART3, ENABLE);
periph_config_release_lock();
gpio_release(GPIOC);
s_initialized = true;
}
static void prv_putchar(uint8_t c) {
if (!s_initialized) {
return;
}
while (USART_GetFlagStatus(USART3, USART_FLAG_TC) == RESET) continue;
USART_SendData(USART3, c);
while (USART_GetFlagStatus(USART3, USART_FLAG_TC) == RESET) continue;
}
static void prv_flush(void) {
uint32_t crc;
size_t raw_length = sizeof(PulseFrame) + sizeof(PushPacket) +
sizeof(s_message_header) + s_message_length + sizeof(crc);
unsigned char raw_packet[raw_length];
PulseFrame *frame = (PulseFrame *)raw_packet;
frame->protocol = hton16(PULSE_TRANSPORT_PUSH);
PushPacket *transport = (PushPacket *)frame->information;
transport->protocol = hton16(PULSE_PROTOCOL_LOGGING);
transport->length = hton16(sizeof(PushPacket) + sizeof(s_message_header) +
s_message_length);
unsigned char *app = transport->information;
memcpy(app, s_message_header, sizeof(s_message_header));
memcpy(&app[sizeof(s_message_header)], s_message_buffer,
s_message_length);
crc = crc32(CRC32_INIT, raw_packet, raw_length - sizeof(crc));
memcpy(&raw_packet[raw_length - sizeof(crc)], &crc, sizeof(crc));
unsigned char cooked_packet[MAX_SIZE_AFTER_COBS_ENCODING(raw_length)];
size_t cooked_length = cobs_encode(cooked_packet, raw_packet, raw_length);
prv_putchar(FRAME_DELIMITER);
for (size_t i = 0; i < cooked_length; ++i) {
if (cooked_packet[i] == FRAME_DELIMITER) {
prv_putchar('\0');
} else {
prv_putchar(cooked_packet[i]);
}
}
prv_putchar(FRAME_DELIMITER);
s_message_length = 0;
}
void dbgserial_putstr(const char* str) {
if (!s_initialized) {
return;
}
dbgserial_print(str);
prv_flush();
}
void dbgserial_print(const char* str) {
if (!s_initialized) {
return;
}
for (; *str && s_message_length < MAX_MESSAGE; ++str) {
if (*str == '\n') {
prv_flush();
} else if (*str != '\r') {
s_message_buffer[s_message_length++] = *str;
}
}
}
void dbgserial_print_hex(uint32_t value) {
char buf[12];
itoa(value, buf, sizeof(buf));
dbgserial_print(buf);
}

View file

@ -0,0 +1,80 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "drivers/gpio.h"
#include <stdint.h>
#define MAX_GPIO (9)
static uint8_t s_gpio_clock_count[MAX_GPIO];
void gpio_use(GPIO_TypeDef* GPIOx) {
uint8_t idx = ((((uint32_t)GPIOx) - AHB1PERIPH_BASE) / 0x0400);
if((idx < MAX_GPIO) && !(s_gpio_clock_count[idx]++)) {
SET_BIT(RCC->AHB1ENR, (0x1 << idx));
}
}
void gpio_release(GPIO_TypeDef* GPIOx) {
uint8_t idx = ((((uint32_t)GPIOx) - AHB1PERIPH_BASE) / 0x0400);
if((idx < MAX_GPIO) && s_gpio_clock_count[idx] && !(--s_gpio_clock_count[idx])) {
CLEAR_BIT(RCC->AHB1ENR, (0x1 << idx));
}
}
void gpio_output_init(OutputConfig pin_config, GPIOOType_TypeDef otype,
GPIOSpeed_TypeDef speed) {
GPIO_InitTypeDef init = {
.GPIO_Pin = pin_config.gpio_pin,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_Speed = speed,
.GPIO_OType = otype,
.GPIO_PuPd = GPIO_PuPd_NOPULL
};
gpio_use(pin_config.gpio);
GPIO_Init(pin_config.gpio, &init);
gpio_release(pin_config.gpio);
}
void gpio_output_set(OutputConfig pin_config, bool asserted) {
if (!pin_config.active_high) {
asserted = !asserted;
}
gpio_use(pin_config.gpio);
GPIO_WriteBit(pin_config.gpio, pin_config.gpio_pin,
asserted? Bit_SET : Bit_RESET);
gpio_release(pin_config.gpio);
}
void gpio_af_init(AfConfig af_config, GPIOOType_TypeDef otype,
GPIOSpeed_TypeDef speed, GPIOPuPd_TypeDef pupd) {
GPIO_InitTypeDef init = {
.GPIO_Pin = af_config.gpio_pin,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_Speed = speed,
.GPIO_OType = otype,
.GPIO_PuPd = pupd
};
gpio_use(af_config.gpio);
GPIO_Init(af_config.gpio, &init);
GPIO_PinAFConfig(af_config.gpio, af_config.gpio_pin_source,
af_config.gpio_af);
gpio_release(af_config.gpio);
}

View file

@ -0,0 +1,772 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "util/misc.h"
#include "drivers/i2c.h"
#include "drivers/periph_config.h"
#include "drivers/gpio.h"
#include "system/passert.h"
#include "system/logging.h"
#include "util/delay.h"
#include <inttypes.h>
#if defined(MICRO_FAMILY_STM32F2)
#include "stm32f2xx_gpio.h"
#include "stm32f2xx_rcc.h"
#include "stm32f2xx_i2c.h"
#elif defined(MICRO_FAMILY_STM32F4)
#include "stm32f4xx_gpio.h"
#include "stm32f4xx_rcc.h"
#include "stm32f4xx_i2c.h"
#include "drivers/pmic.h"
#endif
#define portBASE_TYPE int
#define pdFALSE 0
#define portEND_SWITCHING_ISR(expr) (void)(expr)
#define I2C_ERROR_TIMEOUT_MS (1000)
#define I2C_TIMEOUT_ATTEMPTS_MAX (2 * 1000 * 1000)
#define I2C_NORMAL_MODE_CLOCK_SPEED_MAX (100000)
#define I2C_NACK_COUNT_MAX (1000) // MFI NACKs while busy. We delay ~1ms between retries so this is approximately a 1s timeout
#define I2C_READ_WRITE_BIT (0x01)
typedef struct I2cTransfer {
uint8_t device_address;
bool read_not_write; //True for read, false for write
uint8_t register_address;
uint8_t size;
uint8_t idx;
uint8_t *data;
enum TransferState {
TRANSFER_STATE_WRITE_ADDRESS_TX,
TRANSFER_STATE_WRITE_REG_ADDRESS,
TRANSFER_STATE_REPEAT_START,
TRANSFER_STATE_WRITE_ADDRESS_RX,
TRANSFER_STATE_WAIT_FOR_DATA,
TRANSFER_STATE_READ_DATA,
TRANSFER_STATE_WRITE_DATA,
TRANSFER_STATE_END_WRITE,
TRANSFER_STATE_INVALID,
} state;
bool result;
uint16_t nack_count;
}I2cTransfer;
typedef struct I2cBus{
I2C_TypeDef *i2c;
uint8_t user_count;
I2cTransfer transfer;
volatile bool busy;
}I2cBus;
static I2cBus i2c_buses[BOARD_I2C_BUS_COUNT];
static uint32_t s_guard_events[] = {
I2C_EVENT_MASTER_MODE_SELECT,
I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED,
I2C_EVENT_MASTER_BYTE_TRANSMITTED,
I2C_EVENT_MASTER_MODE_SELECT,
I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED,
I2C_EVENT_MASTER_BYTE_RECEIVED,
I2C_EVENT_MASTER_BYTE_TRANSMITTING,
I2C_EVENT_MASTER_BYTE_TRANSMITTED,
};
static bool s_initialized = false;
/*----------------SEMAPHORE/LOCKING FUNCTIONS--------------------------*/
static void bus_lock(I2cBus *bus) {
}
static void bus_unlock(I2cBus *bus) {
}
static bool semaphore_take(I2cBus *bus) {
return true;
}
static bool semaphore_wait(I2cBus *bus) {
bus->busy = true;
volatile uint32_t timeout_attempts = I2C_TIMEOUT_ATTEMPTS_MAX;
while ((timeout_attempts-- > 0) && (bus->busy));
bus->busy = false;
return (timeout_attempts != 0);
}
static void semaphore_give(I2cBus *bus) {
}
/*-------------------BUS/PIN CONFIG FUNCTIONS--------------------------*/
//! Configure bus power supply control pin as output
//! Lock bus and peripheral config access before configuring pins
void i2c_bus_rail_ctl_config(OutputConfig pin_config) {
gpio_use(pin_config.gpio);
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = pin_config.gpio_pin;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(pin_config.gpio, &GPIO_InitStructure);
gpio_release(pin_config.gpio);
}
//! Configure bus pins for use by I2C peripheral
//! Lock bus and peripheral config access before configuring pins
static void bus_pin_cfg_i2c(AfConfig pin_config) {
gpio_use(pin_config.gpio);
GPIO_InitTypeDef gpio_init_struct;
gpio_init_struct.GPIO_Pin = pin_config.gpio_pin;
gpio_init_struct.GPIO_Mode = GPIO_Mode_AF;
gpio_init_struct.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init_struct.GPIO_OType = GPIO_OType_OD;
gpio_init_struct.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(pin_config.gpio, &gpio_init_struct);
GPIO_PinAFConfig(pin_config.gpio, pin_config.gpio_pin_source, pin_config.gpio_af);
gpio_release(pin_config.gpio);
}
//! Configure bus pin as input
//! Lock bus and peripheral config access before use
static void bus_pin_cfg_input(AfConfig pin_config) {
gpio_use(pin_config.gpio);
// Configure pin as high impedance input
GPIO_InitTypeDef gpio_init_struct;
gpio_init_struct.GPIO_Pin = pin_config.gpio_pin;
gpio_init_struct.GPIO_Mode = GPIO_Mode_IN;
gpio_init_struct.GPIO_Speed = GPIO_Speed_2MHz;
gpio_init_struct.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(pin_config.gpio, &gpio_init_struct);
gpio_release(pin_config.gpio);
}
//! Configure bus pin as output
//! Lock bus and peripheral config access before use
static void bus_pin_cfg_output(AfConfig pin_config, bool pin_state) {
gpio_use(pin_config.gpio);
// Configure pin as output
GPIO_InitTypeDef gpio_init_struct;
gpio_init_struct.GPIO_Pin = pin_config.gpio_pin;
gpio_init_struct.GPIO_Mode = GPIO_Mode_OUT;
gpio_init_struct.GPIO_Speed = GPIO_Speed_2MHz;
gpio_init_struct.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(pin_config.gpio, &gpio_init_struct);
// Set bit high or low
GPIO_WriteBit(pin_config.gpio, pin_config.gpio_pin, (pin_state) ? Bit_SET : Bit_RESET);
gpio_release(pin_config.gpio);
}
//! Power down I2C bus power supply
//! Always lock bus and peripheral config access before use
static void bus_rail_power_down(uint8_t bus_idx) {
if (BOARD_CONFIG.i2c_bus_configs[bus_idx].rail_ctl_fn == NULL) {
return;
}
BOARD_CONFIG.i2c_bus_configs[bus_idx].rail_ctl_fn(false);
// Drain through pull-ups
bus_pin_cfg_output(BOARD_CONFIG.i2c_bus_configs[bus_idx].i2c_scl, false);
bus_pin_cfg_output(BOARD_CONFIG.i2c_bus_configs[bus_idx].i2c_sda, false);
}
//! Power up I2C bus power supply
//! Always lock bus and peripheral config access before use
static void bus_rail_power_up(uint8_t bus_idx) {
if (BOARD_CONFIG.i2c_bus_configs[bus_idx].rail_ctl_fn == NULL) {
return;
}
// check that at least enough time has elapsed since the last turn-off
// TODO: is this necessary in bootloader?
static const uint32_t MIN_STOP_TIME_MS = 10;
delay_ms(MIN_STOP_TIME_MS);
bus_pin_cfg_input(BOARD_CONFIG.i2c_bus_configs[bus_idx].i2c_scl);
bus_pin_cfg_input(BOARD_CONFIG.i2c_bus_configs[bus_idx].i2c_sda);
BOARD_CONFIG.i2c_bus_configs[bus_idx].rail_ctl_fn(true);
}
//! Initialize the I2C peripheral
//! Lock the bus and peripheral config access before initialization
static void bus_init(uint8_t bus_idx) {
// Initialize peripheral
I2C_InitTypeDef i2c_init_struct;
I2C_StructInit(&i2c_init_struct);
if (BOARD_CONFIG.i2c_bus_configs[bus_idx].clock_speed > I2C_NORMAL_MODE_CLOCK_SPEED_MAX) { //Fast mode
i2c_init_struct.I2C_DutyCycle = BOARD_CONFIG.i2c_bus_configs[bus_idx].duty_cycle;
}
i2c_init_struct.I2C_ClockSpeed = BOARD_CONFIG.i2c_bus_configs[bus_idx].clock_speed;
i2c_init_struct.I2C_Ack = I2C_Ack_Enable;
I2C_Init(i2c_buses[bus_idx].i2c, &i2c_init_struct);
I2C_Cmd(i2c_buses[bus_idx].i2c, ENABLE);
}
//! Configure the bus pins, enable the peripheral clock and initialize the I2C peripheral.
//! Always lock the bus and peripheral config access before enabling it
static void bus_enable(uint8_t bus_idx) {
// Don't power up rail if the bus is already in use (enable can be called to reset bus)
if (i2c_buses[bus_idx].user_count == 0) {
bus_rail_power_up(bus_idx);
}
bus_pin_cfg_i2c(BOARD_CONFIG.i2c_bus_configs[bus_idx].i2c_scl);
bus_pin_cfg_i2c(BOARD_CONFIG.i2c_bus_configs[bus_idx].i2c_sda);
// Enable peripheral clock
periph_config_acquire_lock();
periph_config_enable(RCC_APB1PeriphClockCmd, BOARD_CONFIG.i2c_bus_configs[bus_idx].clock_ctrl);
periph_config_release_lock();
bus_init(bus_idx);
}
//! De-initialize and gate the clock to the peripheral
//! Power down rail if the bus supports that and no devices are using it
//! Always lock the bus and peripheral config access before disabling it
static void bus_disable(uint8_t bus_idx) {
I2C_DeInit(i2c_buses[bus_idx].i2c);
periph_config_acquire_lock();
periph_config_disable(RCC_APB1PeriphClockCmd, BOARD_CONFIG.i2c_bus_configs[bus_idx].clock_ctrl);
periph_config_release_lock();
// Do not de-power rail if there are still devices using bus (just reset peripheral and pin configuration during a bus reset)
if (i2c_buses[bus_idx].user_count == 0) {
bus_rail_power_down(bus_idx);
}
else {
bus_pin_cfg_input(BOARD_CONFIG.i2c_bus_configs[bus_idx].i2c_scl);
bus_pin_cfg_input(BOARD_CONFIG.i2c_bus_configs[bus_idx].i2c_sda);
}
}
//! Perform a soft reset of the bus
//! Always lock the bus before reset
static void bus_reset(uint8_t bus_idx) {
bus_disable(bus_idx);
bus_enable(bus_idx);
}
/*---------------INIT/USE/RELEASE/RESET FUNCTIONS----------------------*/
void i2c_init(void) {
for (uint32_t i = 0; i < ARRAY_LENGTH(i2c_buses); i++) {
i2c_buses[i].i2c = BOARD_CONFIG.i2c_bus_configs[i].i2c;
i2c_buses[i].user_count = 0;
i2c_buses[i].busy = false;
i2c_buses[i].transfer.idx = 0;
i2c_buses[i].transfer.size = 0;
i2c_buses[i].transfer.data = NULL;
i2c_buses[i].transfer.state = TRANSFER_STATE_INVALID;
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = BOARD_CONFIG.i2c_bus_configs[i].ev_irq_channel;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0c;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x00;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_InitStructure.NVIC_IRQChannel = BOARD_CONFIG.i2c_bus_configs[i].er_irq_channel;
NVIC_Init(&NVIC_InitStructure);
I2C_DeInit(i2c_buses[i].i2c);
}
s_initialized = true;
for (uint32_t i = 0; i < ARRAY_LENGTH(i2c_buses); i++) {
if (BOARD_CONFIG.i2c_bus_configs[i].rail_cfg_fn) {
BOARD_CONFIG.i2c_bus_configs[i].rail_cfg_fn();
}
if (BOARD_CONFIG.i2c_bus_configs[i].rail_ctl_fn) {
bus_rail_power_down(i);
}
}
}
void i2c_use(I2cDevice device_id) {
PBL_ASSERTN(s_initialized);
PBL_ASSERT(device_id < BOARD_CONFIG.i2c_device_count, "I2C device ID out of bounds %d (max: %d)",
device_id, BOARD_CONFIG.i2c_device_count);
uint8_t bus_idx = BOARD_CONFIG.i2c_device_map[device_id];
I2cBus *bus = &i2c_buses[bus_idx];
bus_lock(bus);
if (bus->user_count == 0) {
bus_enable(bus_idx);
}
bus->user_count++;
bus_unlock(bus);
}
void i2c_release(I2cDevice device_id) {
PBL_ASSERTN(s_initialized);
PBL_ASSERTN(device_id < BOARD_CONFIG.i2c_device_count);
uint8_t bus_idx = BOARD_CONFIG.i2c_device_map[device_id];
I2cBus *bus = &i2c_buses[bus_idx];
bus_lock(bus);
if (bus->user_count == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "Attempted release of disabled bus %d by device %d", bus_idx, device_id);
bus_unlock(bus);
return;
}
bus->user_count--;
if (bus->user_count == 0) {
bus_disable(bus_idx);
}
bus_unlock(bus);
}
void i2c_reset(I2cDevice device_id) {
PBL_ASSERTN(s_initialized);
PBL_ASSERTN(device_id < BOARD_CONFIG.i2c_device_count);
uint8_t bus_idx = BOARD_CONFIG.i2c_device_map[device_id];
I2cBus *bus = &i2c_buses[bus_idx];
// Take control of bus; only one task may use bus at a time
bus_lock(bus);
if (bus->user_count == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "Attempted reset of disabled bus %d by device %d", bus_idx, device_id);
bus_unlock(bus);
return;
}
PBL_LOG(LOG_LEVEL_WARNING, "Resetting I2C bus %" PRId8, bus_idx);
// decrement user count for reset so that if this user is the only user, the
// bus will be powered down during the reset
bus->user_count--;
// Reset and reconfigure bus and pins
bus_reset(bus_idx);
//Restore user count
bus->user_count++;
bus_unlock(bus);
}
/*--------------------DATA TRANSFER FUNCTIONS--------------------------*/
//! Wait a short amount of time for busy bit to clear
static bool wait_for_busy_clear(uint8_t bus_idx) {
unsigned int attempts = I2C_TIMEOUT_ATTEMPTS_MAX;
while((i2c_buses[bus_idx].i2c->SR2 & I2C_SR2_BUSY) != 0) {
--attempts;
if (!attempts) {
return false;
}
}
return true;
}
//! Abort the transfer
//! Should only be called when the bus is locked
static void abort_transfer(I2cBus *bus) {
// Disable all interrupts on the bus
bus->i2c->CR2 &= ~(I2C_CR2_ITEVTEN | I2C_CR2_ITERREN | I2C_CR2_ITBUFEN);
// Generate a stop condition
bus->i2c->CR1 |= I2C_CR1_STOP;
bus->transfer.state = TRANSFER_STATE_INVALID;
}
//! Set up and start a transfer to a device, wait for it to finish and clean up after the transfer has completed
static bool do_transfer(I2cDevice device_id, bool read_not_write, uint8_t device_address, uint8_t register_address, uint8_t size, uint8_t *data) {
PBL_ASSERTN(s_initialized);
PBL_ASSERTN(device_id < BOARD_CONFIG.i2c_device_count);
uint8_t bus_idx = BOARD_CONFIG.i2c_device_map[device_id];
I2cBus *bus = &i2c_buses[bus_idx];
// Take control of bus; only one task may use bus at a time
bus_lock(bus);
if (bus->user_count == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "Attempted access to disabled bus %d by device %d", bus_idx, device_id);
bus_unlock(bus);
return false;
}
// If bus is busy (it shouldn't be as this function waits for the bus to report a non-idle state
// before exiting) reset the bus and wait for it to become not-busy
// Exit if bus remains busy. User module should reset the I2C module at this point
if((bus->i2c->SR2 & I2C_SR2_BUSY) != 0) {
bus_reset(bus_idx);
if (!wait_for_busy_clear(bus_idx)) {
// Bus did not recover after reset
bus_unlock(bus);
return false;
}
}
// Take binary semaphore so that next take will block
PBL_ASSERT(semaphore_take(bus), "Could not acquire semaphore token");
// Set up transfer
bus->transfer.device_address = device_address;
bus->transfer.register_address = register_address;
bus->transfer.read_not_write = read_not_write;
bus->transfer.size = size;
bus->transfer.idx = 0;
bus->transfer.state = TRANSFER_STATE_WRITE_ADDRESS_TX;
bus->transfer.data = data;
bus->transfer.nack_count = 0;
// Ack received bytes
I2C_AcknowledgeConfig(bus->i2c, ENABLE);
bool result = false;
do {
// Generate start event
bus->i2c->CR1 |= I2C_CR1_START;
//Enable event and error interrupts
bus->i2c->CR2 |= I2C_CR2_ITEVTEN | I2C_CR2_ITERREN;
// Wait on semaphore until it is released by interrupt or a timeout occurs
if (semaphore_wait(bus)) {
if (bus->transfer.state == TRANSFER_STATE_INVALID) {
// Transfer is complete
result = bus->transfer.result;
if (!result) {
PBL_LOG(LOG_LEVEL_ERROR, "I2C Error on bus %" PRId8, bus_idx);
}
} else if (bus->transfer.nack_count < I2C_NACK_COUNT_MAX) {
// NACK received after start condition sent: the MFI chip NACKs start conditions whilst it is busy
// Retry start condition after a short delay.
// A NACK count is incremented for each NACK received, so that legitimate NACK
// errors cause the transfer to be aborted (after the NACK count max has been reached).
bus->transfer.nack_count++;
delay_ms(1);
} else {
// Too many NACKs received, abort transfer
abort_transfer(bus);
break;
PBL_LOG(LOG_LEVEL_ERROR, "I2C Error: too many NACKs received on bus %" PRId8, bus_idx);
}
} else {
// Timeout, abort transfer
abort_transfer(bus);
break;
PBL_LOG(LOG_LEVEL_ERROR, "Transfer timed out on bus %" PRId8, bus_idx);
}
} while (bus->transfer.state != TRANSFER_STATE_INVALID);
// Return semaphore token so another transfer can be started
semaphore_give(bus);
// Wait for bus to to clear the busy flag before a new transfer starts
// Theoretically a transfer could complete successfully, but the busy flag never clears,
// which would cause the next transfer to fail
if (!wait_for_busy_clear(bus_idx)) {
// Reset I2C bus if busy flag does not clear
bus_reset(bus_idx);
}
bus_unlock(bus);
return result;
}
bool i2c_read_register(I2cDevice device_id, uint8_t i2c_device_address, uint8_t register_address, uint8_t *result) {
return i2c_read_register_block(device_id, i2c_device_address, register_address, 1, result);
}
bool i2c_read_register_block(I2cDevice device_id, uint8_t i2c_device_address, uint8_t
register_address_start, uint8_t read_size, uint8_t* result_buffer) {
#if defined(TARGET_QEMU)
PBL_LOG(LOG_LEVEL_DEBUG, "i2c reads on QEMU not supported");
return false;
#endif
// Do transfer locks the bus
bool result = do_transfer(device_id, true, i2c_device_address, register_address_start, read_size, result_buffer);
if (!result) {
PBL_LOG(LOG_LEVEL_ERROR, "Read failed on bus %" PRId8, BOARD_CONFIG.i2c_device_map[device_id]);
}
return result;
}
bool i2c_write_register(I2cDevice device_id, uint8_t i2c_device_address, uint8_t register_address,
uint8_t value) {
return i2c_write_register_block(device_id, i2c_device_address, register_address, 1, &value);
}
bool i2c_write_register_block(I2cDevice device_id, uint8_t i2c_device_address, uint8_t
register_address_start, uint8_t write_size, const uint8_t* buffer) {
#if defined(TARGET_QEMU)
PBL_LOG(LOG_LEVEL_DEBUG, "i2c writes on QEMU not supported");
return false;
#endif
// Do transfer locks the bus
bool result = do_transfer(device_id, false, i2c_device_address, register_address_start, write_size, (uint8_t*)buffer);
if (!result) {
PBL_LOG(LOG_LEVEL_ERROR, "Write failed on bus %" PRId8, BOARD_CONFIG.i2c_device_map[device_id]);
}
return result;
}
/*------------------------INTERRUPT FUNCTIONS--------------------------*/
//! End a transfer and disable further interrupts
//! Only call from interrupt functions
static portBASE_TYPE end_transfer_irq(I2cBus *bus, bool result) {
bus->i2c->CR2 &= ~(I2C_CR2_ITEVTEN | I2C_CR2_ITERREN | I2C_CR2_ITBUFEN);
bus->i2c->CR1 |= I2C_CR1_STOP;
bus->transfer.result = result;
bus->transfer.state = TRANSFER_STATE_INVALID;
bus->busy = false;
return pdFALSE;
}
//! Pause a transfer, disabling interrupts during the pause
//! Only call from interrupt functions
static portBASE_TYPE pause_transfer_irq(I2cBus *bus) {
bus->i2c->CR2 &= ~(I2C_CR2_ITEVTEN | I2C_CR2_ITERREN | I2C_CR2_ITBUFEN);
bus->busy = false;
return pdFALSE;
}
//! Handle an IRQ event on the specified \a bus
static portBASE_TYPE irq_event_handler(I2cBus *bus) {
if (bus->transfer.state == TRANSFER_STATE_INVALID) {
// Disable interrupts if spurious interrupt received
bus->i2c->CR2 &= ~(I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN);
return pdFALSE;
}
// Check that the expected event occurred
if (I2C_CheckEvent(bus->i2c, s_guard_events[bus->transfer.state]) == ERROR) {
// Ignore interrupt - A spurious byte transmitted event as well as an interrupt with no
// discernible event associated with it occur after repeat start events are generated
return pdFALSE;
}
portBASE_TYPE should_context_switch = pdFALSE;
switch (bus->transfer.state) {
case TRANSFER_STATE_WRITE_ADDRESS_TX:
// Write the i2c device address to the bus to select it in write mode.
bus->i2c->DR = bus->transfer.device_address & ~I2C_READ_WRITE_BIT;
bus->transfer.state = TRANSFER_STATE_WRITE_REG_ADDRESS;
break;
case TRANSFER_STATE_WRITE_REG_ADDRESS:
// Write the register address
bus->i2c->DR = bus->transfer.register_address;
if (bus->transfer.read_not_write) {
bus->transfer.state = TRANSFER_STATE_REPEAT_START;
} else {
// Enable TXE interrupt for writing
bus->i2c->CR2 |= I2C_CR2_ITBUFEN;
bus->transfer.state = TRANSFER_STATE_WRITE_DATA;
}
break;
case TRANSFER_STATE_REPEAT_START:
// Generate a repeat start
bus->i2c->CR1 |= I2C_CR1_START;
bus->transfer.state = TRANSFER_STATE_WRITE_ADDRESS_RX;
break;
case TRANSFER_STATE_WRITE_ADDRESS_RX:
// Write the I2C device address again, but this time in read mode.
bus->i2c->DR = bus->transfer.device_address | I2C_READ_WRITE_BIT;
if (bus->transfer.size == 1) {
// Last byte, we want to NACK this one to tell the slave to stop sending us bytes.
bus->i2c->CR1 &= ~I2C_CR1_ACK;
}
bus->transfer.state = TRANSFER_STATE_WAIT_FOR_DATA;
break;
case TRANSFER_STATE_WAIT_FOR_DATA:
//This state just ensures that the transition to receive mode event happened
// Enable RXNE interrupt for writing
bus->i2c->CR2 |= I2C_CR2_ITBUFEN;
bus->transfer.state = TRANSFER_STATE_READ_DATA;
break;
case TRANSFER_STATE_READ_DATA:
bus->transfer.data[bus->transfer.idx] = bus->i2c->DR;
bus->transfer.idx++;
if (bus->transfer.idx + 1 == bus->transfer.size) {
// Last byte, we want to NACK this one to tell the slave to stop sending us bytes.
bus->i2c->CR1 &= ~I2C_CR1_ACK;
}
else if (bus->transfer.idx == bus->transfer.size) {
// End transfer after all bytes have been received
bus->i2c->CR2 &= ~I2C_CR2_ITBUFEN;
should_context_switch = end_transfer_irq(bus, true);
break;
}
break;
case TRANSFER_STATE_WRITE_DATA:
bus->i2c->DR = bus->transfer.data[bus->transfer.idx];
bus->transfer.idx++;
if (bus->transfer.idx == bus->transfer.size) {
bus->i2c->CR2 &= ~I2C_CR2_ITBUFEN;
bus->transfer.state = TRANSFER_STATE_END_WRITE;
break;
}
break;
case TRANSFER_STATE_END_WRITE:
// End transfer after all bytes have been sent
should_context_switch = end_transfer_irq(bus, true);
break;
default:
// Abort transfer from invalid state - should never reach here (state machine logic broken)
should_context_switch = end_transfer_irq(bus, false);
break;
}
return should_context_switch;
}
//! Handle error interrupt on the specified \a bus
static portBASE_TYPE irq_error_handler(I2cBus *bus) {
if (bus->transfer.state == TRANSFER_STATE_INVALID) {
// Disable interrupts if spurious interrupt received
bus->i2c->CR2 &= ~I2C_CR2_ITERREN;
return pdFALSE;
}
// Data overrun and bus errors can only really be handled by terminating the transfer and
// trying to recover bus to an idle state. Each error will be logged. In each case a stop
// condition will be sent and then we will wait on the busy flag to clear (if it doesn't,
// a soft reset of the bus will be performed (handled in wait i2c_do_transfer).
if ((bus->i2c->SR1 & I2C_SR1_OVR) != 0) {
bus->i2c->SR1 &= ~I2C_SR1_OVR;
// Data overrun
PBL_LOG(LOG_LEVEL_ERROR, "Data overrun during I2C transaction; Bus: 0x%p", bus->i2c);
}
if ((bus->i2c->SR1 & I2C_SR1_BERR) != 0) {
bus->i2c->SR1 &= ~I2C_SR1_BERR;
// Bus error: invalid start or stop condition detected
PBL_LOG(LOG_LEVEL_ERROR, "Bus error detected during I2C transaction; Bus: 0x%p", bus->i2c);
}
if ((bus->i2c->SR1 & I2C_SR1_AF) != 0) {
bus->i2c->SR1 &= ~I2C_SR1_AF;
// NACK received.
//
// The MFI chip will cause NACK errors during read operations after writing a start bit (first start
// or repeat start indicating that it is busy. The transfer must be paused and the start condition sent
// again after a delay and the state machine set back a step.
//
// If the NACK is received after any other action log an error and abort the transfer
if (bus->transfer.state == TRANSFER_STATE_WAIT_FOR_DATA) {
bus->transfer.state = TRANSFER_STATE_WRITE_ADDRESS_RX;
return pause_transfer_irq(bus);
}
else if (bus->transfer.state == TRANSFER_STATE_WRITE_REG_ADDRESS){
bus->transfer.state = TRANSFER_STATE_WRITE_ADDRESS_TX;
return pause_transfer_irq(bus);
}
else {
PBL_LOG(LOG_LEVEL_ERROR, "NACK received during I2C transfer; Bus: 0x%p", bus->i2c);
}
}
return end_transfer_irq(bus, false);
}
void I2C1_EV_IRQHandler(void) {
portEND_SWITCHING_ISR(irq_event_handler(&i2c_buses[0]));
}
void I2C1_ER_IRQHandler(void) {
portEND_SWITCHING_ISR(irq_error_handler(&i2c_buses[0]));
}
void I2C2_EV_IRQHandler(void) {
portEND_SWITCHING_ISR(irq_event_handler(&i2c_buses[1]));
}
void I2C2_ER_IRQHandler(void) {
portEND_SWITCHING_ISR(irq_error_handler(&i2c_buses[1]));
}
/*------------------------COMMAND FUNCTIONS--------------------------*/
void command_power_2v5(char *arg) {
// Intentionally ignore the s_running_count and make it so!
// This is intended for low level electrical test only
if(!strcmp("on", arg)) {
bus_rail_power_up(1);
} else {
bus_rail_power_down(1);
}
}

View file

@ -0,0 +1,108 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <stdbool.h>
#include "drivers/pmic.h"
#include "drivers/gpio.h"
#include "util/delay.h"
#include "board/board.h"
#if defined(MICRO_FAMILY_STM32F2)
#include "stm32f2xx_gpio.h"
#include "stm32f2xx_rcc.h"
#include "stm32f2xx_i2c.h"
#elif defined(MICRO_FAMILY_STM32F4)
#include "stm32f4xx_gpio.h"
#include "stm32f4xx_rcc.h"
#include "stm32f4xx_i2c.h"
#include "drivers/pmic.h"
#endif
extern void i2c_bus_rail_ctl_config(OutputConfig pin_config);
static void do_rail_power(bool up, GPIO_TypeDef* const gpio, const uint32_t gpio_pin, const bool active_high) {
if (up) {
gpio_use(gpio);
// enable the bus supply
GPIO_WriteBit(gpio, gpio_pin, active_high ? Bit_SET : Bit_RESET);
// wait for the bus supply to stabilize and the peripherals to start up.
// the MFI chip requires its reset pin to be stable for at least 10ms from startup.
delay_ms(20);
gpio_release(gpio);
} else {
gpio_use(gpio);
// disable the bus supply
GPIO_WriteBit(gpio, gpio_pin, active_high ? Bit_RESET : Bit_SET);
gpio_release(gpio);
}
}
// SNOWY
/////////
void snowy_i2c_rail_1_ctl_fn(bool enable) {
set_ldo3_power_state(enable);
}
// bb2
/////////
void bb2_rail_ctl_fn(bool enable) {
do_rail_power(enable, GPIOH, GPIO_Pin_0, true);
}
void bb2_rail_cfg_fn(void) {
i2c_bus_rail_ctl_config((OutputConfig){ GPIOH, GPIO_Pin_0, true});
}
// v1_5
/////////
void v1_5_rail_ctl_fn(bool enable) {
do_rail_power(enable, GPIOH, GPIO_Pin_0, true);
}
void v1_5_rail_cfg_fn(void) {
i2c_bus_rail_ctl_config((OutputConfig){ GPIOH, GPIO_Pin_0, true});
}
// v2_0
/////////
void v2_0_rail_ctl_fn(bool enable) {
do_rail_power(enable, GPIOH, GPIO_Pin_0, true);
}
void v2_0_rail_cfg_fn(void) {
i2c_bus_rail_ctl_config((OutputConfig){ GPIOH, GPIO_Pin_0, true});
}
// ev2_4
/////////
void ev2_4_rail_ctl_fn(bool enable) {
do_rail_power(enable, GPIOH, GPIO_Pin_0, true);
}
void ev2_4_rail_cfg_fn(void) {
i2c_bus_rail_ctl_config((OutputConfig){ GPIOH, GPIO_Pin_0, true});
}
// bigboard
////////////
void bigboard_rail_ctl_fn(bool enable) {
do_rail_power(enable, GPIOC, GPIO_Pin_5, true);
}
void bigboard_rail_cfg_fn(void) {
i2c_bus_rail_ctl_config((OutputConfig){ GPIOC, GPIO_Pin_5, true});
}

View file

@ -0,0 +1,60 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "drivers/spi.h"
#include "util/misc.h"
#include "system/passert.h"
#if defined(MICRO_FAMILY_STM32F2)
#include "stm32f2xx_rcc.h"
#elif defined(MICRO_FAMILY_STM32F4)
#include "stm32f4xx_rcc.h"
#endif
// Deduced by looking at the prescalers in stm32f2xx_spi.h
#define SPI_FREQ_LOG_TO_PRESCALER(LG) (((LG) - 1) * 0x8)
uint16_t spi_find_prescaler(uint32_t bus_frequency, SpiPeriphClock periph_clock) {
// Get the clocks
RCC_ClocksTypeDef clocks;
RCC_GetClocksFreq(&clocks);
uint32_t clock = 0;
// Find which peripheral clock we belong to
if (periph_clock == SpiPeriphClockAPB1) {
clock = clocks.PCLK1_Frequency;
} else if (periph_clock == SpiPeriphClockAPB2) {
clock = clocks.PCLK2_Frequency;
} else {
WTF;
}
int lg;
if (bus_frequency > (clock / 2)) {
lg = 1; // Underclock to the highest possible frequency
} else {
uint32_t divisor = clock / bus_frequency;
lg = ceil_log_two(divisor);
}
// Prescalers only exists for values in [2 - 256] range
PBL_ASSERTN(lg > 0);
PBL_ASSERTN(lg < 9);
// return prescaler
return (SPI_FREQ_LOG_TO_PRESCALER(lg));
}

View file

@ -0,0 +1,131 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "drivers/system_flash.h"
#include "drivers/dbgserial.h"
#include "util/misc.h"
#if defined(MICRO_FAMILY_STM32F2)
#include "stm32f2xx_flash.h"
#elif defined(MICRO_FAMILY_STM32F4)
#include "stm32f4xx_flash.h"
#endif
static uint16_t s_sectors[] = {
FLASH_Sector_0, FLASH_Sector_1, FLASH_Sector_2, FLASH_Sector_3,
FLASH_Sector_4, FLASH_Sector_5, FLASH_Sector_6, FLASH_Sector_7,
FLASH_Sector_8, FLASH_Sector_9, FLASH_Sector_10, FLASH_Sector_11 };
static uint32_t s_sector_addresses[] = {
ADDR_FLASH_SECTOR_0, ADDR_FLASH_SECTOR_1, ADDR_FLASH_SECTOR_2,
ADDR_FLASH_SECTOR_3, ADDR_FLASH_SECTOR_4, ADDR_FLASH_SECTOR_5,
ADDR_FLASH_SECTOR_6, ADDR_FLASH_SECTOR_7, ADDR_FLASH_SECTOR_8,
ADDR_FLASH_SECTOR_9, ADDR_FLASH_SECTOR_10, ADDR_FLASH_SECTOR_11 };
int prv_get_sector_num_for_address(uint32_t address) {
if (address < s_sector_addresses[0]) {
dbgserial_print("address ");
dbgserial_print_hex(address);
dbgserial_print(" is outside system flash\r\n");
return -1;
}
for (size_t i=0; i < ARRAY_LENGTH(s_sector_addresses)-1; ++i) {
if (s_sector_addresses[i] <= address
&& address < s_sector_addresses[i+1]) {
return i;
}
}
return ARRAY_LENGTH(s_sector_addresses)-1;
}
bool system_flash_erase(
uint32_t address, size_t length,
SystemFlashProgressCb progress_callback, void *progress_context) {
dbgserial_print("system_flash_erase(");
dbgserial_print_hex(address);
dbgserial_print(", ");
dbgserial_print_hex(length);
dbgserial_print(")\r\n");
if (length == 0) {
// Nothing to do
return true;
}
int first_sector = prv_get_sector_num_for_address(address);
int last_sector = prv_get_sector_num_for_address(address + length - 1);
if (first_sector < 0 || last_sector < 0) {
return false;
}
int count = last_sector - first_sector + 1;
if (progress_callback) {
progress_callback(0, count, progress_context);
}
FLASH_Unlock();
for (int sector = first_sector; sector <= last_sector; ++sector) {
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |
FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
if (FLASH_EraseSector(
s_sectors[sector], VoltageRange_1) != FLASH_COMPLETE) {
dbgserial_print("failed to erase sector ");
dbgserial_print_hex(sector);
dbgserial_putstr("");
FLASH_Lock();
return false;
}
if (progress_callback) {
progress_callback(sector - first_sector + 1, count, progress_context);
}
}
FLASH_Lock();
return true;
}
bool system_flash_write(
uint32_t address, const void *data, size_t length,
SystemFlashProgressCb progress_callback, void *progress_context) {
dbgserial_print("system_flash_write(");
dbgserial_print_hex(address);
dbgserial_print(", ");
dbgserial_print_hex(length);
dbgserial_print(")\r\n");
FLASH_Unlock();
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |
FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR|FLASH_FLAG_PGSERR);
const uint8_t *data_array = data;
for (uint32_t i = 0; i < length; ++i) {
if (FLASH_ProgramByte(address + i, data_array[i]) != FLASH_COMPLETE) {
dbgserial_print("failed to write address ");
dbgserial_print_hex(address);
dbgserial_putstr("");
FLASH_Lock();
return false;
}
if (progress_callback && i % 128 == 0) {
progress_callback(i/128, length/128, progress_context);
}
}
FLASH_Lock();
return true;
}
uint32_t system_flash_read(uint32_t address) {
uint32_t data = *(volatile uint32_t*) address;
return data;
}

View file

@ -0,0 +1,61 @@
/*
* Copyright 2024 Google LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "drivers/watchdog.h"
#include "util/bitset.h"
#include "system/logging.h"
#if defined(MICRO_FAMILY_STM32F2)
#include "stm32f2xx_dbgmcu.h"
#include "stm32f2xx_iwdg.h"
#include "stm32f2xx_rcc.h"
#elif defined(MICRO_FAMILY_STM32F4)
#include "stm32f4xx_dbgmcu.h"
#include "stm32f4xx_iwdg.h"
#include "stm32f4xx_rcc.h"
#endif
#include <inttypes.h>
void watchdog_init(void) {
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
IWDG_SetPrescaler(IWDG_Prescaler_64); // ~8 seconds
IWDG_SetReload(0xfff);
IWDG_WriteAccessCmd(IWDG_WriteAccess_Disable);
DBGMCU_APB1PeriphConfig(DBGMCU_IWDG_STOP, ENABLE);
}
void watchdog_start(void) {
IWDG_Enable();
watchdog_feed();
}
// This behaves differently from the bootloader and the firmware.
void watchdog_feed(void) {
IWDG_ReloadCounter();
}
bool watchdog_check_reset_flag(void) {
return RCC_GetFlagStatus(RCC_FLAG_IWDGRST) != RESET;
}
void watchdog_clear_reset_flag(void) {
RCC_ClearFlag();
}