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

2
src/fw/drivers/README.md Normal file
View file

@ -0,0 +1,2 @@
Before editing a driver or writing a new one, please read through the
[driver coding guidelines on Confluence](https://pebbletechnology.atlassian.net/wiki/x/tIFQAw).

210
src/fw/drivers/accel.h Normal file
View file

@ -0,0 +1,210 @@
/*
* 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.
*/
#pragma once
#include "services/imu/units.h"
#include <inttypes.h>
#include <stdbool.h>
#include <stdint.h>
/*! Accelerometer driver interface
* ==============================
*
* The accelerometer driver is simply an interface to the accelerometer
* hardware. It is dumb; it does not contain any circular buffers, has no
* knowledge of clients, threads, subsampling or even other hardware. It is up
* to higher level code (read: the accelerometer service) to deal with
* that. The reason for that is to maximize code reuse: anything which could
* possibly need to be copy-pasted from one accel driver to another should be
* moved outside of the driver.
*
* The accelerometer knows (almost) nothing about the OS, events, analytics or
* the vibe motor. It does not even keep around a sample buffer for any reason.
* All of that code is handled externally. The interface for the accelerometer
* driver is a set of functions implemented by the accelerometer, and a set of
* external functions that it will call in response to certain events. While OS
* services may be employed internally by a driver, they are not part of the
* public interface.
*
* One of the goals of the accelerometer interface is to hide the state of the
* accelerometer hardware as much as possible (e.g. FIFO mode) and use
* higher-level constructs to allow the driver to make its own decisions on what
* state the hardware should be in. This way the interface is (hopefully)
* generic enough that accelerometers with vastly different operating and
* power-saving modes can have all of those details hidden away in the driver,
* and the higher-level code can work unmodified with different accelerometers.
*/
//! Information which varies by accelerometer driver.
typedef struct {
//! Highest sample interval (slowest rate) supported by the driver.
uint32_t sample_interval_max;
//! Recommended sample interval for low-power use, around 100,000 us.
uint32_t sample_interval_low_power;
//! Recommended sample interval for interactive use, around 250,000 us.
uint32_t sample_interval_ui;
//! Recommended sample interval for games and fast interactivity,
//! around 20,000 us.
uint32_t sample_interval_game;
//! Lowest sample interval (fastest rate) supported by the driver.
uint32_t sample_interval_min;
} AccelDriverInfo;
extern const AccelDriverInfo ACCEL_DRIVER_INFO;
typedef struct {
//! Timestamp of when the sample was taken in microseconds since the epoch.
//! The precision of the timestamp is not guaranteed.
uint64_t timestamp_us;
//! Acceleration along the x axis.
int16_t x;
//! Acceleration along the y axis.
int16_t y;
//! Acceleration along the z axis.
int16_t z;
} AccelDriverSample;
//! Sets the accelerometer sampling interval.
//!
//! Not all sampling intervals are supported by all drivers. The driver must
//! select a sampling interval which is equal to or shorter than the requested
//! interval, saturating at the shortest interval supported by the hardware.
//!
//! The new sampling rate takes effect immediately. The driver may flush any
//! queued samples before changing the sampling rate to ensure that timestamps
//! remain accurate.
//!
//! @param interval_us The requested sampling interval in microseconds.
//!
//! @return The actual sampling interval set by the driver.
uint32_t accel_set_sampling_interval(uint32_t interval_us);
//! Returns the currently set accelerometer sampling interval.
uint32_t accel_get_sampling_interval(void);
//! Set the max number of samples the driver may batch.
//!
//! @param n Maximum number of samples the driver can batch
//!
//! When n=0, the accelerometer driver must not call accel_cb_new_sample().
//!
//! When n=1, the accelerometer driver must call accel_cb_new_sample() for
//! each sample as soon as the hardware has acquired it.
//!
//! When n>1, the accelerometer driver may batch up to n samples before
//! calling accel_cb_new_sample() up to n times in rapid succession with
//! all of the queued samples. The last item in a batch must be the most
//! recently acquired sample from the hardware. This is used by the driver
//! as a hint for power saving or other optimizations; it only sets an
//! upper bound on the number of samples the driver may batch up.
//!
//! When n is set to a value smaller than the number of samples already
//! queued up, the driver must flush all of the queued samples to
//! accel_cb_new_sample() before the new value of n takes effect. The
//! accel_cb_new_sample() function may be called from within
//! accel_set_num_samples().
//!
//! @see accel_cb_new_sample
void accel_set_num_samples(uint32_t num_samples);
//! Peek at the most recent accelerometer sample.
//!
//! @param[out] data Pointer to a buffer to write accelerometer data
//!
//! @return 0 if successful, nonzero on failure
//!
//! During the execution of this function, the driver may call
//! accel_cb_new_sample() one or more times iff accel_set_num_samples(n) was
//! called most recently with a value of n >= 1.
int accel_peek(AccelDriverSample *data);
//! Enable or disable shake detection
//!
//! @param on Enable shake detection when true, disable when false
//!
//! When shake detection is enabled, accel_cb_shake_detected must be called every
//! time the accelerometer hardware detects a shake. When shake detection is
//! disabled, accel_cb_shake_detected must not be called.
//!
//! @see accel_cb_shake_detected
void accel_enable_shake_detection(bool on);
//! Returns whether shake detection is enabled
bool accel_get_shake_detection_enabled(void);
//! Enable or disable double tap detection
//!
//! @param on Enable double tap detection when true, disable when false
//!
//! When double tap detection is enabled, accel_cb_double_tap_detected must be called every
//! time the accelerometer hardware detects a double tap. When double tap detection is
//! disabled, accel_cb_double_tap_detected must not be called.
//!
//! @see accel_cb_double_tap_detected
void accel_enable_double_tap_detection(bool on);
//! Returns whether double tap detection is enabled
bool accel_get_double_tap_detection_enabled(void);
//! Function called by the driver whenever a new accel sample is available.
//!
//! @param[in] data pointer to a populated AccelDriverSample struct. The pointer is
//! only valid for the duration of the function call.
//!
//! This function will always be called with samples monotonically increasing in
//! time. It will always be called from within a thread context.
//!
//! @note This function may be called from within any of the functions in the
//! accelerometer driver interface. To prevent reentrancy issues, avoid
//! calling accelerometer driver functions from within this function.
extern void accel_cb_new_sample(AccelDriverSample const *data);
//! Function called by driver whenever shake is detected.
//!
//! @param axis Axis which the shake was detected on
//! @param direction The sign indicates whether the shake was on the positive or
//! negative axis
//!
//! @note It is up to the implementer to filter out shake events triggered by the
//! vibrate motor.
extern void accel_cb_shake_detected(IMUCoordinateAxis axis, int32_t direction);
//! Function called by driver whenever a double tap is detected.
//!
//! @param axis Axis which the double tap was detected on
//! @param direction The sign indicates whether the double tap was on the positive or
//! negative axis
extern void accel_cb_double_tap_detected(IMUCoordinateAxis axis, int32_t direction);
//! Function called by driver when it needs to offload work from an ISR context.
//! It is up to the implementer to decide how this should work
//!
//! @param cb The callback to be invoked from a thread context
//! @param data Data to be passed to the callback, NULL if none
typedef void (*AccelOffloadCallback)(void);
extern void accel_offload_work_from_isr(AccelOffloadCallback cb, bool *should_context_switch);
//! Function runs a diagnostic test on the accelerometer hardware to confirm it
//! works as expected
extern bool accel_run_selftest(void);
//! The accelerometer supports a changeable sensitivity for shake detection. This call will
//! select whether we want the accelerometer to enter a highly sensitive state with a low
//! threshold, where any minor amount of motion would trigger the system shake event.
//! Note: Setting this value does not ensure that shake detection is enabled.
void accel_set_shake_sensitivity_high(bool sensitivity_high);

576
src/fw/drivers/accessory.c Normal file
View file

@ -0,0 +1,576 @@
/*
* 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/accessory.h"
#include "board/board.h"
#include "console/console_internal.h"
#include "console/serial_console.h"
#include "console/prompt.h"
#include "drivers/dma.h"
#include "drivers/gpio.h"
#include "drivers/exti.h"
#include "drivers/periph_config.h"
#include "drivers/uart.h"
#include "kernel/util/stop.h"
#include "mcu/interrupts.h"
#include "os/mutex.h"
#include "os/tick.h"
#include "services/common/new_timer/new_timer.h"
#include "services/common/system_task.h"
#include "system/logging.h"
#include "system/passert.h"
#include "kernel/util/delay.h"
#include "kernel/util/sleep.h"
#include "util/attributes.h"
#include "util/likely.h"
#include "util/size.h"
#include "FreeRTOS.h" /* FreeRTOS Kernal Prototypes/Constants. */
#include "semphr.h"
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
//! The default baudrate for the accessory UART.
#define DEFAULT_BAUD AccessoryBaud115200
//! How long each interval should be in milliseconds.
#define ACCESSORY_STOP_INTERVAL_PERIOD_MS (250)
//! How many intervals we should wait outside of stop mode when we first see any noise on the
//! serial port.
#define ACCESSORY_INITIAL_STOP_INTERVALS (500 / ACCESSORY_STOP_INTERVAL_PERIOD_MS)
//! How many intervals we should wait outside of stop mode when we first see valid data on the
//! serial port.
#define ACCESSORY_VALID_DATA_STOP_INTERVALS (3000 / ACCESSORY_STOP_INTERVAL_PERIOD_MS)
//! How many bytes of send history to keep. This needs to be 3 bytes because the TX buffer will be
//! moved into the shift register (with a new byte being loaded into the buffer) before we receive
//! the byte we previously sent. So, when we receive a byte, we will have sent 2 more bytes by then.
#define SEND_HISTORY_LENGTH (1)
//! Within accessory_send_stream(), how long we wait for a byte to be sent before timing-out.
#define SEND_BYTE_TIMEOUT_MS (100)
//! We DMA into this buffer as a circular buffer
#define RX_BUFFER_LENGTH (200)
static uint8_t DMA_BSS s_rx_buffer[RX_BUFFER_LENGTH];
//! The current baud rate
static uint32_t s_baudrate;
//! Whether or not the accessory power is enabled
static bool s_power_enabled;
//! Whether or not we are in input mode (receiving)
static bool s_input_enabled;
//! We'll store up to the last 3 bytes which were sent for detecting bus contention
typedef struct {
uint8_t data;
bool has_data;
} SendHistory;
static volatile SendHistory s_send_history;
//! Flag which states whether or not we've detected bus contention since last disabling input
static volatile bool s_bus_contention_detected;
//! Whether or not we sent data since disabling input
static bool s_sent_data;
//! The callback for a stream being sent via accessory_send_stream()
static volatile AccessoryDataStreamCallback s_stream_cb;
//! Context passed to accessory_send_stream()
static void *s_stream_context;
//! Semaphore used for accessory_send_stream()
static SemaphoreHandle_t s_send_semaphore;
//! Mutex used for accessory_block() / accessory_unblock()
static PebbleRecursiveMutex *s_blocked_lock;
//! Used to track whether or not the accessory_send_stream callback sent a new byte via
//! accessory_send_byte()
static volatile bool s_did_send_byte;
//! Whether or not we should use DMA for receiving
static bool s_use_dma;
//! Whether or not DMA is enabled
static bool s_dma_enabled;
//! Used by accessory_send_stream() to track whether or not we've sent a byte recently
static volatile bool s_has_sent_byte;
//! We need to disable stop mode in order to receive data on the accessory connector. To do this,
//! we set up an exti that kicks us out of stop mode when data is seen. Then, we schedule a timer
//! to check for additional data being seen on the connector. If we go 5 seconds without seeing
//! data, we can go back into stop mode.
static struct {
//! If the accessory connector is currently active...
bool active;
//! The timer that will fire once a second while we're active
TimerID timer;
//! How many intervals have gone by without data being seen
int intervals_without_data;
//! How many intervals we should wait for without data before going back into stop mode
int max_intervals_without_data;
//! If we saw data on the connector since the last time the timer fired.
bool data_seen_this_interval;
} s_stop_mode_monitor;
static bool prv_rx_irq_handler(UARTDevice *dev, uint8_t data, const UARTRXErrorFlags *err_flags);
static bool prv_tx_irq_handler(UARTDevice *dev);
static void prv_lock(void) {
if (mcu_state_is_isr()) {
// assume we're in an ISR for the UART and don't need to worry about being blocked
return;
}
mutex_lock_recursive(s_blocked_lock);
}
static void prv_unlock(void) {
if (mcu_state_is_isr()) {
// assume we're in an ISR for the UART and don't need to worry about being blocked
return;
}
mutex_unlock_recursive(s_blocked_lock);
}
static void prv_enable_dma(void) {
PBL_ASSERTN(!s_dma_enabled);
s_dma_enabled = true;
uart_start_rx_dma(ACCESSORY_UART, s_rx_buffer, sizeof(s_rx_buffer));
}
static void prv_disable_dma(void) {
if (!s_dma_enabled) {
return;
}
s_dma_enabled = false;
uart_stop_rx_dma(ACCESSORY_UART);
}
//! The interval timer callback.
static void prv_timer_interval_expired_cb(void *data) {
if (!s_stop_mode_monitor.data_seen_this_interval) {
// The accessory connector didn't have any data since the last time this callback fired.
++s_stop_mode_monitor.intervals_without_data;
if (s_stop_mode_monitor.intervals_without_data >=
s_stop_mode_monitor.max_intervals_without_data) {
// Enough intervals have passed and we should now turn stop mode back on.
stop_mode_enable(InhibitorAccessory);
s_stop_mode_monitor.active = false;
s_stop_mode_monitor.intervals_without_data = 0;
s_stop_mode_monitor.max_intervals_without_data = 0;
new_timer_stop(s_stop_mode_monitor.timer);
}
} else {
// Data was seen, reset the interval counter
s_stop_mode_monitor.intervals_without_data = 0;
}
// Regardless of what happened, this interval is over and should be reset
s_stop_mode_monitor.data_seen_this_interval = false;
}
static void prv_start_timer_cb(void *context) {
new_timer_start(s_stop_mode_monitor.timer, ACCESSORY_STOP_INTERVAL_PERIOD_MS,
prv_timer_interval_expired_cb, NULL, TIMER_START_FLAG_REPEATING);
}
//! Callback run whenever the EXTI fires
static void prv_exti_cb(bool *should_context_switch) {
if (!s_stop_mode_monitor.active) {
// First time seeing data, let's go active
s_stop_mode_monitor.active = true;
s_stop_mode_monitor.intervals_without_data = 0;
s_stop_mode_monitor.max_intervals_without_data = ACCESSORY_INITIAL_STOP_INTERVALS;
stop_mode_disable(InhibitorAccessory);
// Need to flip tasks because we can't start a timer from an interrupt
system_task_add_callback_from_isr(prv_start_timer_cb, NULL, should_context_switch);
}
s_stop_mode_monitor.data_seen_this_interval = true;
}
//! The UART peripheral only runs if the accessory is not in stop mode. We listen to the txrx
//! pin on the accessory connector and if we see anything we'll disable stop mode for a few
//! seconds to see if anyone has something to say.
static void prv_initialize_exti(void) {
s_stop_mode_monitor.timer = new_timer_create();
gpio_input_init(&BOARD_CONFIG_ACCESSORY.int_gpio);
exti_configure_pin(BOARD_CONFIG_ACCESSORY.exti, ExtiTrigger_Falling, prv_exti_cb);
exti_enable(BOARD_CONFIG_ACCESSORY.exti);
}
static void prv_initialize_uart(uint32_t baudrate) {
#if RECOVERY_FW
// In PRF / MFG, we'll have a strong (2k) external pull-up, so we should always be open-drain
const bool is_open_drain = true;
#else
// If we raise the baud rate above 115200 we need to configure as push-pull to ensure we are
// sufficiently driving the line. Ideally, the accessory would have a strong-enough pull-up, but
// now that we've released use of the accessory port via the smartstrap APIs, we can't easily
// change this.
const bool is_open_drain = (baudrate <= 115200);
#endif
s_baudrate = baudrate;
if (is_open_drain) {
uart_init_open_drain(ACCESSORY_UART);
} else {
uart_init(ACCESSORY_UART);
}
uart_set_rx_interrupt_handler(ACCESSORY_UART, prv_rx_irq_handler);
uart_set_tx_interrupt_handler(ACCESSORY_UART, prv_tx_irq_handler);
uart_set_baud_rate(ACCESSORY_UART, s_baudrate);
uart_set_rx_interrupt_enabled(ACCESSORY_UART, true);
}
static void prv_initialize_hardware(void) {
periph_config_acquire_lock();
gpio_output_init(&BOARD_CONFIG_ACCESSORY.power_en, GPIO_OType_PP, GPIO_Speed_2MHz);
gpio_output_set(&BOARD_CONFIG_ACCESSORY.power_en, false); // Turn power off
accessory_set_baudrate(DEFAULT_BAUD);
periph_config_release_lock();
prv_initialize_exti();
}
static void prv_set_baudrate(uint32_t baudrate, bool force_update) {
if ((baudrate != s_baudrate) || force_update) {
PBL_LOG(LOG_LEVEL_DEBUG, "Changing accessory connector baud rate to %"PRIu32, baudrate);
prv_initialize_uart(baudrate);
if (s_dma_enabled) {
// we need to reset DMA after resetting the UART
prv_disable_dma();
prv_enable_dma();
}
}
}
void accessory_init(void) {
s_send_semaphore = xSemaphoreCreateBinary();
xSemaphoreGive(s_send_semaphore);
s_blocked_lock = mutex_create_recursive();
prv_initialize_hardware();
accessory_set_power(false);
accessory_enable_input();
}
void accessory_block(void) {
prv_lock();
accessory_send_stream_stop();
uart_deinit(ACCESSORY_UART);
}
void accessory_unblock(void) {
// We want to restore the previous baudrate, but clear s_baudrate in order to force a complete
// re-init of the peripheral.
prv_set_baudrate(s_baudrate, true /* force_update */);
prv_unlock();
}
void accessory_send_byte(uint8_t data) {
// NOTE: this may be run within an ISR
prv_lock();
s_has_sent_byte = true;
s_did_send_byte = true;
PBL_ASSERTN(!s_input_enabled);
while (!(uart_is_tx_ready(ACCESSORY_UART))) continue;
// this section needs to be atomic since the UART IRQ also modifies these variables
portENTER_CRITICAL();
if (s_send_history.has_data) {
// The send buffer is full. This means that the receive interrupt hasn't fired to clear the
// buffer which indicates that there is bus contention preventing a stop bit from occuring.
s_bus_contention_detected = true;
} else {
s_send_history.data = data;
s_send_history.has_data = true;
}
portEXIT_CRITICAL();
uart_write_byte(ACCESSORY_UART, data);
s_sent_data = true;
prv_unlock();
}
void accessory_send_data(const uint8_t *data, size_t length) {
// NOTE: this may be run within an ISR
prv_lock();
// When sending data, we need to temporarily disable input, as there's only one data line for
// both directions and any data we send on that line will also be interpreted as data we can
// read. This means there's a bit of overhead for sending data as we have to also make sure
// we don't accidentally read it back. If you're going to be sending a large amount of data,
// calling accessory_disable_input before will give you a nice speed boost as we don't have
// to wait for it to be safe to turn the input back on after each byte.
const bool temporarily_disabled = s_input_enabled;
if (UNLIKELY(temporarily_disabled)) {
accessory_disable_input();
}
for (size_t i = 0; i < length; ++i) {
accessory_send_byte(data[i]);
}
if (UNLIKELY(temporarily_disabled)) {
accessory_enable_input();
}
prv_unlock();
}
bool accessory_send_stream(AccessoryDataStreamCallback stream_callback, void *context) {
bool success = true;
prv_lock();
PBL_ASSERTN(xSemaphoreTake(s_send_semaphore, portMAX_DELAY) == pdPASS);
PBL_ASSERTN(stream_callback != NULL);
PBL_ASSERTN(!s_input_enabled);
if (s_dma_enabled) {
uart_clear_rx_dma_buffer(ACCESSORY_UART);
}
s_stream_context = context;
s_stream_cb = stream_callback;
s_has_sent_byte = false;
uart_set_tx_interrupt_enabled(ACCESSORY_UART, true);
// Block until the sending is complete, but timeout if we aren't able to send a byte for a while.
while (xSemaphoreTake(s_send_semaphore, milliseconds_to_ticks(SEND_BYTE_TIMEOUT_MS)) != pdPASS) {
if (!s_has_sent_byte) {
// we haven't sent a byte in the last timeout period, so time out the whole send
s_stream_cb = NULL;
s_stream_context = NULL;
success = false;
PBL_LOG(LOG_LEVEL_ERROR, "Timed-out while sending");
break;
}
s_has_sent_byte = false;
}
xSemaphoreGive(s_send_semaphore);
prv_unlock();
return success;
}
void accessory_send_stream_stop(void) {
prv_lock();
if (s_stream_cb) {
// wait for any in-progress write to finish
PBL_ASSERTN(xSemaphoreTake(s_send_semaphore, portMAX_DELAY) == pdPASS);
xSemaphoreGive(s_send_semaphore);
}
uart_set_tx_interrupt_enabled(ACCESSORY_UART, false);
s_stream_cb = NULL;
s_stream_context = NULL;
prv_unlock();
}
void accessory_disable_input(void) {
// NOTE: This function may be called from an ISR
prv_lock();
PBL_ASSERTN(s_input_enabled);
s_input_enabled = false;
s_send_history.has_data = false;
s_bus_contention_detected = false;
prv_unlock();
}
void accessory_enable_input(void) {
// NOTE: This function may be called from an ISR
if (s_input_enabled) {
return;
}
prv_lock();
if (s_sent_data) {
// wait for the TC flag to be set
uart_wait_for_tx_complete(ACCESSORY_UART);
// wait a little for the lines to settle down
const uint32_t us_to_wait = (1000000 / s_baudrate) * 2;
delay_us(us_to_wait);
s_sent_data = false;
}
// Read data and throw it away to clear the state. We don't want to handle data we received
// while input was disabled
uart_read_byte(ACCESSORY_UART);
s_input_enabled = true;
prv_unlock();
}
void accessory_use_dma(bool use_dma) {
prv_lock();
s_use_dma = use_dma;
if (s_use_dma) {
prv_enable_dma();
} else {
prv_disable_dma();
}
prv_unlock();
}
bool accessory_bus_contention_detected(void) {
return s_bus_contention_detected;
}
static uint32_t prv_get_baudrate(AccessoryBaud baud_select) {
const uint32_t BAUDS[] = { 9600, 14400, 19200, 28800, 38400, 57600, 62500, 115200, 125000, 230400,
250000, 460800, 921600 };
_Static_assert(ARRAY_LENGTH(BAUDS) == AccessoryBaudInvalid,
"bauds table doesn't match up with AccessoryBaud enum");
return BAUDS[baud_select];
}
void accessory_set_baudrate(AccessoryBaud baud_select) {
prv_lock();
PBL_ASSERTN(baud_select < AccessoryBaudInvalid);
prv_set_baudrate(prv_get_baudrate(baud_select), false /* !force_update */);
prv_unlock();
}
void accessory_set_power(bool on) {
if (on == s_power_enabled) {
return;
}
PBL_LOG(LOG_LEVEL_DEBUG, "Setting accessory power %s", on?"on":"off");
s_power_enabled = on;
gpio_output_set(&BOARD_CONFIG_ACCESSORY.power_en, on);
}
bool accessory_is_present(void) {
accessory_set_power(true);
gpio_input_init_pull_up_down(&BOARD_CONFIG_ACCESSORY.int_gpio, GPIO_PuPd_DOWN);
// budget for a capacitance up to ~1uF and a resistance of 10kOhm
psleep(10);
bool result = (gpio_input_read(&BOARD_CONFIG_ACCESSORY.int_gpio) == SET);
gpio_input_init(&BOARD_CONFIG_ACCESSORY.int_gpio);
return result;
}
// ISRs
////////////////////////////////////////////////////////////////////
static bool prv_rx_irq_handler(UARTDevice *dev, uint8_t data, const UARTRXErrorFlags *err_flags) {
bool should_context_switch = false;
// We've now seen valid data on the serial port, make sure we stay out of stop mode for a
// longer period of time.
s_stop_mode_monitor.max_intervals_without_data = ACCESSORY_VALID_DATA_STOP_INTERVALS;
if (s_input_enabled) {
// we are receiving data from the accessory
if (!err_flags->framing_error) {
should_context_switch = accessory_manager_handle_character_from_isr((char)data);
} else if (data == 0x00) {
should_context_switch = accessory_manager_handle_break_from_isr();
}
} else {
// we are receiving data we just sent since the RX/TX lines are tied together
if (s_send_history.has_data) {
if (s_send_history.data != data) {
// The byte we are receiving doesn't match the next byte in the send queue.
s_bus_contention_detected = true;
}
s_send_history.has_data = false;
} else {
// We received a byte without sending and the input is not enabled. This typically indicates
// a race condition between when we disable input and start sending, or between when we
// finish sending and enable input. Either way, we can't trust this data so treat it as bus
// contention.
s_bus_contention_detected = true;
}
}
if (s_stream_cb) {
// enable the TXE interrupt for sending the next byte
uart_set_tx_interrupt_enabled(dev, true);
}
return should_context_switch;
}
static bool prv_tx_irq_handler(UARTDevice *dev) {
bool should_context_switch = false;
if (s_stream_cb && !s_send_history.has_data) {
s_did_send_byte = false;
if (s_stream_cb(s_stream_context)) {
// the callback MUST send a byte in order for this interrupt to trigger again
PBL_ASSERTN(s_did_send_byte);
} else {
// we're done sending
portBASE_TYPE was_higher_task_woken = pdFALSE;
xSemaphoreGiveFromISR(s_send_semaphore, &was_higher_task_woken);
should_context_switch = (was_higher_task_woken != pdFALSE);
uart_set_tx_interrupt_enabled(dev, false);
s_stream_cb = NULL;
s_stream_context = NULL;
}
} else {
// we haven't yet received back the byte we sent
uart_set_tx_interrupt_enabled(dev, false);
}
return should_context_switch;
}
// Commands
////////////////////////////////////////////////////////////////////
void command_accessory_power_set(const char *on) {
if (!strcmp(on, "on")) {
accessory_set_power(true);
} else if (!strcmp(on, "off")) {
accessory_set_power(false);
} else {
prompt_send_response("Usage: accessory power (on|off)");
}
}
static volatile int32_t s_num_test_bytes;
static bool prv_test_send_stream(void *context) {
accessory_send_byte((uint8_t)s_num_test_bytes);
if (accessory_bus_contention_detected()) {
return false;
}
return (--s_num_test_bytes > 0);
}
void command_accessory_stress_test(void) {
if (s_baudrate != prv_get_baudrate(DEFAULT_BAUD)) {
prompt_send_response("FAILED: accessory port is busy");
return;
}
// send 1 second worth of data
s_num_test_bytes = 46080;
accessory_use_dma(true);
accessory_set_baudrate(AccessoryBaud460800);
accessory_disable_input();
const bool success = accessory_send_stream(prv_test_send_stream, NULL);
accessory_enable_input();
accessory_set_baudrate(DEFAULT_BAUD);
accessory_use_dma(false);
char buffer[50];
if (!success) {
prompt_send_response_fmt(buffer, sizeof(buffer), "FAILED: send timed-out");
} else if (s_num_test_bytes == 0) {
prompt_send_response_fmt(buffer, sizeof(buffer), "PASS!");
} else {
prompt_send_response_fmt(buffer, sizeof(buffer), "FAILED: %"PRId32" bytes left!",
s_num_test_bytes);
}
}

108
src/fw/drivers/accessory.h Normal file
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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "services/common/system_task.h"
//! Different speeds we support running the accessory connector at.
//!
//! @internal
//! Please keep this enum in order from lowest speed to highest.
typedef enum {
AccessoryBaud9600,
AccessoryBaud14400,
AccessoryBaud19200,
AccessoryBaud28800,
AccessoryBaud38400,
AccessoryBaud57600,
AccessoryBaud62500,
AccessoryBaud115200,
AccessoryBaud125000,
AccessoryBaud230400,
AccessoryBaud250000,
AccessoryBaud460800,
AccessoryBaud921600,
AccessoryBaudInvalid
} AccessoryBaud;
//! The type of function used for ISR-based sending via accessory_send_stream(). This function MUST
//! send a single byte by calling accessory_send_byte() and/or return false to indicate that there
//! is no more data to be sent.
typedef bool (*AccessoryDataStreamCallback)(void *context);
//! Initialize the accessory driver
void accessory_init(void);
//! Blocks the accessory port from being used
void accessory_block(void);
//! Unblocks the accessory port and allows it to be used
void accessory_unblock(void);
//! Enable power output on the accessory connector.
void accessory_set_power(bool on);
//! Send a single byte synchronously out the accessory connector. Input must be disabled before
//! calling this function.
void accessory_send_byte(uint8_t data);
//! Send data synchronously out the accessory connector. Will return once all data has been sent.
void accessory_send_data(const uint8_t *data, size_t length);
//! Sends data using ISRs by calling the provided function to send the next byte until the stream
//! callback returns false to indicate sending is complete or bus contention is detected
bool accessory_send_stream(AccessoryDataStreamCallback stream_callback, void *context);
//! Stops any ISR-based sending which is in progress
void accessory_send_stream_stop(void);
//! Stop the driver from reading any input on the accessory port. When input is disabled we can
//! write out the accessory port at higher rates as we don't have to worry about supressing
//! reading back our own output.
void accessory_disable_input(void);
//! Allow the driver to start receiving input again. Only valid after calling
//! accessory_disable_input.
void accessory_enable_input(void);
//! Set the baudrate
void accessory_set_baudrate(AccessoryBaud baud_select);
//! Called from the accessory UART interrupt. The manager is responsible for implementing this
//! function.
//! @return whether we need to trigger a context switch based on handling this character
bool accessory_manager_handle_character_from_isr(char c);
//! Called from the accessory UART interrupt. The manager is responsible for implementing this
//! function.
//! @return whether we need to trigger a context switch based on handling this character
bool accessory_manager_handle_break_from_isr(void);
//! Returns whether or not there has been bus contention detected since accessory_disable_input()
//! was last called.
bool accessory_bus_contention_detected(void);
//! Checks if the pull-up resistor which is required for smarstraps is present
bool accessory_is_present(void);
//! Uses DMA for receiving from the peripheral
void accessory_use_dma(bool use_dma);

View file

@ -0,0 +1,154 @@
/*
* 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 "board/board.h"
#include "console/prompt.h"
#include "drivers/ambient_light.h"
#include "drivers/gpio.h"
#include "drivers/voltage_monitor.h"
#include "drivers/periph_config.h"
#include "kernel/util/sleep.h"
#include "mfg/mfg_info.h"
#include "system/logging.h"
#include "system/passert.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#include <inttypes.h>
static uint32_t s_sensor_light_dark_threshold;
static bool s_initialized = false;
static uint32_t prv_get_default_ambient_light_dark_threshold(void) {
switch (mfg_info_get_watch_color()) {
// stepped white bezel
case WATCH_INFO_COLOR_TIME_ROUND_ROSE_GOLD_14:
case WATCH_INFO_COLOR_TIME_ROUND_SILVER_14:
return 3200;
case WATCH_INFO_COLOR_TIME_ROUND_BLACK_14:
case WATCH_INFO_COLOR_TIME_ROUND_SILVER_20:
return 3330;
case WATCH_INFO_COLOR_TIME_ROUND_BLACK_20:
return 3430;
default:
PBL_ASSERTN(BOARD_CONFIG.ambient_light_dark_threshold != 0);
return BOARD_CONFIG.ambient_light_dark_threshold;
}
}
//! Turn on or off the ambient light sensor.
//! @param enable True to turn the light sensor on, false to turn it off.
static void prv_sensor_enable(bool enable) {
const BitAction set = enable ? Bit_SET : Bit_RESET;
gpio_use(BOARD_CONFIG.photo_en.gpio);
GPIO_WriteBit(BOARD_CONFIG.photo_en.gpio, BOARD_CONFIG.photo_en.gpio_pin, set);
gpio_release(BOARD_CONFIG.photo_en.gpio);
}
void ambient_light_init(void) {
s_sensor_light_dark_threshold = prv_get_default_ambient_light_dark_threshold();
periph_config_acquire_lock();
// Initialize light sensor enable
{
gpio_use(BOARD_CONFIG.photo_en.gpio);
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = BOARD_CONFIG.photo_en.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_DOWN;
GPIO_Init(BOARD_CONFIG.photo_en.gpio, &GPIO_InitStructure);
GPIO_WriteBit(BOARD_CONFIG.photo_en.gpio, BOARD_CONFIG.photo_en.gpio_pin, Bit_RESET);
gpio_release(BOARD_CONFIG.photo_en.gpio);
}
if (BOARD_CONFIG.als_always_on) {
prv_sensor_enable(true);
}
periph_config_release_lock();
s_initialized = true;
}
uint32_t ambient_light_get_light_level(void) {
if (!s_initialized) {
return BOARD_CONFIG.ambient_light_dark_threshold;
}
if (!BOARD_CONFIG.als_always_on) {
prv_sensor_enable(true);
}
VoltageReading reading;
voltage_monitor_read(VOLTAGE_MONITOR_ALS, &reading);
if (!BOARD_CONFIG.als_always_on) {
prv_sensor_enable(false);
}
// Multiply vmon/vref * 2/3 to find a percentage of the full scale and then
// multiply it back by 4096 to get a full 12-bit light level.
uint32_t value = (reading.vmon_total * 4096 * 2) / (reading.vref_total * 3);
return value;
}
void command_als_read(void) {
char buffer[16];
prompt_send_response_fmt(buffer, sizeof(buffer), "%"PRIu32"", ambient_light_get_light_level());
}
uint32_t ambient_light_get_dark_threshold(void) {
return s_sensor_light_dark_threshold;
}
void ambient_light_set_dark_threshold(uint32_t new_threshold) {
PBL_ASSERTN(new_threshold <= AMBIENT_LIGHT_LEVEL_MAX);
s_sensor_light_dark_threshold = new_threshold;
}
bool ambient_light_is_light(void) {
// if the sensor is not enabled, always return that it is dark
return s_initialized && ambient_light_get_light_level() > s_sensor_light_dark_threshold;
}
AmbientLightLevel ambient_light_level_to_enum(uint32_t light_level) {
if (!s_initialized) {
// if the sensor is not enabled, always return that it is very dark
return AmbientLightLevelUnknown;
}
const uint32_t k_delta_threshold = BOARD_CONFIG.ambient_k_delta_threshold;
if (light_level < (s_sensor_light_dark_threshold - k_delta_threshold)) {
return AmbientLightLevelVeryDark;
} else if (light_level < s_sensor_light_dark_threshold) {
return AmbientLightLevelDark;
} else if (light_level < (s_sensor_light_dark_threshold + k_delta_threshold)) {
return AmbientLightLevelLight;
} else {
return AmbientLightLevelVeryLight;
}
}

View file

@ -0,0 +1,54 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
//! Light level enum
typedef enum AmbientLightLevel {
AmbientLightLevelUnknown = 0,
AmbientLightLevelVeryDark,
AmbientLightLevelDark,
AmbientLightLevelLight,
AmbientLightLevelVeryLight,
} AmbientLightLevel;
#define AMBIENT_LIGHT_LEVEL_ENUM_COUNT (AmbientLightLevelVeryLight + 1)
static const uint32_t AMBIENT_LIGHT_LEVEL_MAX = 4096; // max 12 bits
/** Initialize the ambient light sensor */
void ambient_light_init(void);
/** get the ambient light level scaled between 0 and AMBIENT_LIGHT_LEVEL_MAX
*/
uint32_t ambient_light_get_light_level(void);
//! get the threshold between light and dark
uint32_t ambient_light_get_dark_threshold(void);
//! set the threshold between light and dark
void ambient_light_set_dark_threshold(uint32_t new_threshold);
//! figure out whether it is light outside
bool ambient_light_is_light();
//! Convert a light level obtained from ambient_light_get_light_level() into an
//! AmbientLightLevel enum value.
//! @param[in] light_level the raw light level reading obtained from ambient_light_get_light_level
AmbientLightLevel ambient_light_level_to_enum(uint32_t light_level);

181
src/fw/drivers/backlight.c Normal file
View file

@ -0,0 +1,181 @@
/*
* 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/backlight.h"
#include <string.h>
#include <stdlib.h>
#include "board/board.h"
#include "debug/power_tracking.h"
#include "console/prompt.h"
#include "drivers/gpio.h"
#include "drivers/led_controller.h"
#include "drivers/periph_config.h"
#include "drivers/pwm.h"
#include "drivers/timer.h"
#include "kernel/util/stop.h"
#include "system/logging.h"
#include "system/passert.h"
// Parameters to a timer based PWM.
//
// ---------------- ---------- ---------- ---------- ----------
// | | | | | | | |
// | | | | | | | |
// | | | | | | | |
// | | | | | | | |
// | | | | | | | |
// | | | | | | | |
// | | | | | | | |
// ------- ------- ------- --------
//
// The resulting waveform has a frequency of PWM_OUTPUT_FREQUENCY_HZ. Inside each period, the timer
// counts up to TIMER_PERIOD_RESOLUTION. This means the counter increments at a rate of
// PWM_OUTPUT_FREQUENCY_HZ * TIMER_PERIOD_RESOLUTION, which is the frequency that our timer
// prescalar has to calculate. The duty cycle is defined by the TIM_Pulse parameter, which
// controls after which counter value the output waveform will become active. For example, a
// TIM_Pulse value of TIMER_PERIOD_RESOLUTION / 4 will result in an output waveform that will go
// active after 25% of it's period has elapsed.
//! The counter reload value. The timer will count from 0 to this value and then reset again.
//! The TIM_Pulse member below controls for how many of these counts the resulting PWM signal is
//! active for.
static const uint32_t TIMER_PERIOD_RESOLUTION = 1024;
//! The number of periods we have per second.
//! Note that we want BOARD_CONFIG_BACKLIGHT.timer.peripheral to have as short a period as
//! possible for power reasons.
static const uint32_t PWM_OUTPUT_FREQUENCY_HZ = 256;
static bool s_initialized = false;
static bool s_backlight_pwm_enabled = false;
//! Bitmask of who wants to hold the LED enable on.
//! see \ref led_enable, \ref led_disable, \ref LEDEnabler
static uint32_t s_led_enable;
static void prv_backlight_pwm_enable(bool on) {
pwm_enable(&BOARD_CONFIG_BACKLIGHT.pwm, on);
if (on != s_backlight_pwm_enabled) {
if (on) {
stop_mode_disable(InhibitorBacklight);
} else {
stop_mode_enable(InhibitorBacklight);
}
}
s_backlight_pwm_enabled = on;
}
void backlight_init(void) {
if (s_initialized) {
return;
}
s_led_enable = 0;
if (BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_Ctl) {
periph_config_acquire_lock();
gpio_output_init(&BOARD_CONFIG_BACKLIGHT.ctl, GPIO_OType_PP, GPIO_Speed_2MHz);
gpio_output_set(&BOARD_CONFIG_BACKLIGHT.ctl, false);
periph_config_release_lock();
s_initialized = true;
}
if (BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_Pwm) {
periph_config_acquire_lock();
pwm_init(&BOARD_CONFIG_BACKLIGHT.pwm,
TIMER_PERIOD_RESOLUTION,
TIMER_PERIOD_RESOLUTION * PWM_OUTPUT_FREQUENCY_HZ);
periph_config_release_lock();
s_initialized = true;
}
if (BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_IssiI2C) {
led_controller_init();
s_initialized = true;
}
}
// TODO: PBL-36077 Move to a generic 4v5 enable
void led_enable(LEDEnabler enabler) {
if (s_led_enable == 0) {
gpio_output_set(&BOARD_CONFIG_BACKLIGHT.ctl, true);
}
s_led_enable |= enabler;
}
// TODO: PBL-36077 Move to a generic 4v5 disable
void led_disable(LEDEnabler enabler) {
s_led_enable &= ~enabler;
if (s_led_enable == 0) {
gpio_output_set(&BOARD_CONFIG_BACKLIGHT.ctl, false);
}
}
void backlight_set_brightness(uint16_t brightness) {
if (BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_Ctl) {
if (brightness == 0) {
led_disable(LEDEnablerBacklight);
} else {
led_enable(LEDEnablerBacklight);
}
}
if (BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_Pwm) {
if (brightness == 0) {
if (s_backlight_pwm_enabled) {
prv_backlight_pwm_enable(false);
}
PWR_TRACK_BACKLIGHT("OFF", PWM_OUTPUT_FREQUENCY_HZ, 0);
} else {
if (!s_backlight_pwm_enabled) {
prv_backlight_pwm_enable(true);
}
// By setting higher values in the TIM_Pulse register, we're causing the output waveform
// to be low for a longer period of time, which causes the backlight to be brighter.
//
// The brightness value has a range of 0 to 0x3fff which is 2^15. The period of the timer
// counter is 2^10. We want to rescale the brightness range into a subset of the timer
// counter range. Different boards will have a different duty cycle that represent the
// "fully on" state.
const uint32_t pwm_scaling_factor = BACKLIGHT_BRIGHTNESS_MAX / TIMER_PERIOD_RESOLUTION;
const uint32_t desired_duty_cycle = brightness * BOARD_CONFIG.backlight_max_duty_cycle_percent
/ pwm_scaling_factor / 100;
pwm_set_duty_cycle(&BOARD_CONFIG_BACKLIGHT.pwm, desired_duty_cycle);
PWR_TRACK_BACKLIGHT("ON", PWM_OUTPUT_FREQUENCY_HZ,
(desired_duty_cycle * 100) / TIMER_PERIOD_RESOLUTION);
}
}
if (BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_IssiI2C) {
led_controller_backlight_set_brightness(brightness >> 8);
}
}
void command_backlight_ctl(const char *arg) {
const int bright_percent = atoi(arg);
if (bright_percent < 0 || bright_percent > 100) {
prompt_send_response("Invalid Brightness");
return;
}
backlight_set_brightness((BACKLIGHT_BRIGHTNESS_MAX * bright_percent) / 100);
prompt_send_response("OK");
}

View file

@ -0,0 +1,43 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
typedef enum {
LEDEnablerNone = (1 << 0),
LEDEnablerBacklight = (1 << 1),
LEDEnablerHRM = (1 << 2),
} LEDEnabler;
// The light brightness can vary between LIGHT_BRIGHTNESS_OFF and LIGHT_BRIGHTNESS_ON
#define BACKLIGHT_BRIGHTNESS_OFF 0x0000
#define BACKLIGHT_BRIGHTNESS_MAX 0x4000
void backlight_init(void);
//! @param brightness a number between BACKLIGHT_BRIGHTNESS_OFF and BACKLIGHT_BRIGHTNESS_ON
void backlight_set_brightness(uint16_t brightness);
//! On some boards, the LED enable gpio is actually a toggle for 4.5v.
//! Other portions of the system may require this to be enabled in order to function.
//! Keep track of who is using the LED enable so that way we don't turn it off on them.
//! Those components which may need to toggle LED Enable are listed in \ref LEDEnabler.
void led_enable(LEDEnabler enabler);
void led_disable(LEDEnabler enabler);

77
src/fw/drivers/battery.h Normal file
View file

@ -0,0 +1,77 @@
/*
* 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.
*/
#pragma once
#include <inttypes.h>
#include <stdbool.h>
/* TODO ***************************************************************
* Some of the comments in this file may not be accurate for snowy.
* Some thought should go into making sure that the function names and
* comments are relevant to both snowy and previous generations
* ********************************************************************/
void battery_init(void);
/** @returns the battery voltage after smoothing and averaging
*/
int battery_get_millivolts(void);
/** @returns true if the battery charge controller thinks we are charging.
* This is often INCORRECT on Pebble Steel due to the additional current
* draw from the LED when charging, and as a result, this is not
* the definition of "charging" we use for most places in the
* code (i.e. battery_get_charge_state().is_charging), which depends on
* SoC percentage. If you are not the battery_monitor state machine,
* you probably don't want to use this. See PBL-2538 for context.
*/
bool battery_charge_controller_thinks_we_are_charging(void);
/** @returns true if both:
* - the USB voltage is higher than 3.15V
* - the USB voltage is higher than the battery voltage
*/
bool battery_is_usb_connected(void);
void battery_set_charge_enable(bool charging_enabled);
void battery_set_fast_charge(bool fast_charge_enabled);
// These are used by battery_common to allow forcing of charge states
bool battery_is_usb_connected_impl(void);
bool battery_charge_controller_thinks_we_are_charging_impl(void);
void battery_force_charge_enable(bool is_charging);
//! The current voltage numbers from the battery. These structs are created by
//! the battery_read_voltage_monitor struct. Each _total value is a sum of 40 samples where
//! each sample is a number between 0 and 4095 representing a value between 0 and 1.8V. See
//! the comments inside battery_convert_reading_to_millivolts to see how to convert this to a
//! useful value.
typedef struct ADCVoltageMonitorReading {
uint32_t vref_total;
uint32_t vmon_total;
} ADCVoltageMonitorReading;
//! Read voltage numbers through an ADC on the voltage monitor pin. This is usually hooked up
//! to the battery voltage, but can be also used to read voltages on other rails by configuring
//! the PMIC to different values.
ADCVoltageMonitorReading battery_read_voltage_monitor(void);
//! Convert a ADCVoltageMonitorReading into a single mV reading using a given dividing ratio.
//! @param numerator The numerator to multiply the result by.
//! @param denominator The denominator to divide the result by.
uint32_t battery_convert_reading_to_millivolts(ADCVoltageMonitorReading reading,
uint32_t numerator, uint32_t denominator);

View file

@ -0,0 +1,53 @@
/*
* 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/battery.h"
uint32_t battery_convert_reading_to_millivolts(ADCVoltageMonitorReading reading,
uint32_t numerator, uint32_t denominator) {
// The result from the ADC is 0-1.8V, but scaled into a 12bit number. That means a value of
// zero indicates 0V and a value of 4095 (2^12 - 1) indicates a reading of 1.8V.
// The ADC is only capable of measuring between 0 and 1.8V, so we expect the thing providing
// a voltage to the monitor pin to be scaling it in some way. This scaling factor is captured
// in the numerator and denominator arguments.
// Therefore, whatever 12-bit number we read from the ADC needs to be converted to a voltage by
// multiplying it by 1.8/4095, and then further scaled into it's final voltage by multiplying by
// numerator and dividing by the denominator.
// Finally, our reading contains a sum of many readings from both the monitor pin as well as
// an internal 1.2V reference voltage. The reason for this is that these pins will have noise
// on them and we can assume that any ripple on the mon rail will also occur on the 1.2V internal
// reference voltage. So, we can measure the voltage synchronously on both ADCs and then
// calculate a relative voltage. Therefore, the actual monitor voltage can be estimated by
// calculating 1800 * (vmon_mv_sum / (vref_mv_sum * 1800 / 1200) or
// 1800 * (vmon_mv_sum * 1200) / (vref_mv_sum * 1800).
// Convert from 12-bit to millivolts by multiplying by 1800/4095 which is the same as 40/91
const uint32_t vref_mv_sum = reading.vref_total * 40 / 91;
const uint32_t vmon_mv_sum = reading.vmon_total * 40 / 91;
// Use the reference voltage to convert a single smoothed out mv reading.
// Multiply vmon/vref * 2/3 to find a percentage of the full scale and then multiply it back
// by 1800 to get back to mV.
const uint32_t millivolts = ((vmon_mv_sum * 1800 * 2) / (vref_mv_sum * 3));
// Finally, hit it with the scaling factors.
const uint32_t scaled_millivolts = millivolts * numerator / denominator;
return scaled_millivolts;
}

View file

@ -0,0 +1,57 @@
/*
* 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/battery.h"
#include "board/board.h"
#include "drivers/voltage_monitor.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include <string.h>
static bool s_charging_forced_disable = false;
ADCVoltageMonitorReading battery_read_voltage_monitor(void) {
VoltageReading info;
voltage_monitor_read(VOLTAGE_MONITOR_BATTERY, &info);
return (ADCVoltageMonitorReading) {
.vref_total = info.vref_total,
.vmon_total = info.vmon_total,
};
}
bool battery_charge_controller_thinks_we_are_charging(void) {
if (s_charging_forced_disable) {
return false;
}
return battery_charge_controller_thinks_we_are_charging_impl();
}
bool battery_is_usb_connected(void) {
if (s_charging_forced_disable) {
return false;
}
return battery_is_usb_connected_impl();
}
void battery_force_charge_enable(bool charging_enabled) {
s_charging_forced_disable = !charging_enabled;
battery_set_charge_enable(charging_enabled);
}

View file

@ -0,0 +1,67 @@
/*
* 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/battery.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/pmic.h"
#include "system/logging.h"
#include "system/passert.h"
void battery_init(void) {
// pmic_init() needs to happen, but I think it will happen elsewhere first
// It may be okay to just init the pmic here again
return;
}
int battery_get_millivolts(void) {
if (!pmic_enable_battery_measure()) {
PBL_LOG(LOG_LEVEL_WARNING, "Failed to enable battery measure. "
"Battery voltage reading will be bogus.");
}
ADCVoltageMonitorReading info = battery_read_voltage_monitor();
pmic_disable_battery_measure();
PBL_ASSERTN(BOARD_CONFIG_POWER.battery_vmon_scale.denominator);
return battery_convert_reading_to_millivolts(info,
BOARD_CONFIG_POWER.battery_vmon_scale.numerator,
BOARD_CONFIG_POWER.battery_vmon_scale.denominator);
}
bool battery_charge_controller_thinks_we_are_charging_impl(void) {
return pmic_is_charging();
}
bool battery_is_usb_connected_impl(void) {
return pmic_is_usb_connected();
}
void battery_set_charge_enable(bool charging_enabled) {
pmic_set_charger_state(charging_enabled);
}
// TODO
// This is my understanding from Figure 9 of the datasheet:
// Charger off -> Pre charge -> Fast Charge (constant current) ->
// Fast Charge (constant voltage) -> Maintain Charge -> Maintain Charge Done
//
// The Pre Charge and Charge Termination currents are programmed via I2C
// The Fast Charge current is determined by Rset
//
// There doesn't seem to be a way to change the current in constant current mode
void battery_set_fast_charge(bool fast_charge_enabled) {
return;
}

View file

@ -0,0 +1,245 @@
/*
* 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/battery.h"
#include "drivers/exti.h"
#include "drivers/gpio.h"
#include "board/board.h"
#include "drivers/otp.h"
#include "drivers/periph_config.h"
#include "system/logging.h"
#define STM32F2_COMPATIBLE
#include <mcu.h>
#include <stdlib.h>
#include <string.h>
#include "kernel/events.h"
#include "services/common/system_task.h"
#include "services/common/new_timer/new_timer.h"
#include "os/tick.h"
#include "FreeRTOS.h"
#include "timers.h"
static const uint32_t USB_CONN_DEBOUNCE_MS = 400;
static TimerID s_debounce_timer_handle = TIMER_INVALID_ID;
static bool s_debounced_is_usb_connected = false;
static bool battery_is_usb_connected_raw(void);
static void battery_vusb_interrupt_handler(bool *should_context_switch);
static void battery_conn_debounce_callback(void* data) {
s_debounced_is_usb_connected = battery_is_usb_connected_raw();
if (!s_debounced_is_usb_connected) {
// disconnection event
// - put the watch charger into a sane state
// - disable fast-charge and re-enable the charger
battery_set_charge_enable(true);
battery_set_fast_charge(false);
}
PebbleEvent event = {
.type = PEBBLE_BATTERY_CONNECTION_EVENT,
.battery_connection = {
.is_connected = s_debounced_is_usb_connected,
}
};
event_put(&event);
}
static bool board_has_chg_fast() {
return BOARD_CONFIG_POWER.chg_fast.gpio != 0;
}
static bool board_has_chg_en() {
return BOARD_CONFIG_POWER.chg_en.gpio != 0;
}
// These are the guts of battery_set_charge_enable(), called when we already have periph_config_acquire_lock
static void prv_battery_set_charge_enable(bool charging_enabled) {
if (board_has_chg_en()) {
gpio_use(BOARD_CONFIG_POWER.chg_en.gpio);
GPIO_WriteBit(BOARD_CONFIG_POWER.chg_en.gpio, BOARD_CONFIG_POWER.chg_en.gpio_pin, charging_enabled?Bit_SET:Bit_RESET);
gpio_release(BOARD_CONFIG_POWER.chg_en.gpio);
PBL_LOG(LOG_LEVEL_DEBUG, "Charging:%s", charging_enabled?"enabled":"disabled");
}
}
// These are the guts of battery_set_fast_charge(), called when we already have periph_config_acquire_lock
static void prv_battery_set_fast_charge(bool fast_charge_enabled) {
if (board_has_chg_fast()) {
gpio_use(BOARD_CONFIG_POWER.chg_fast.gpio);
GPIO_WriteBit(BOARD_CONFIG_POWER.chg_fast.gpio, BOARD_CONFIG_POWER.chg_fast.gpio_pin, fast_charge_enabled?Bit_RESET:Bit_SET);
gpio_release(BOARD_CONFIG_POWER.chg_fast.gpio);
PBL_LOG(LOG_LEVEL_DEBUG, "Fastcharge %s", fast_charge_enabled?"enabled":"disabled");
}
}
void battery_init(void) {
s_debounce_timer_handle = new_timer_create();
periph_config_acquire_lock();
gpio_use(BOARD_CONFIG_POWER.vusb_stat.gpio);
gpio_use(BOARD_CONFIG_POWER.chg_stat.gpio);
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Pin = BOARD_CONFIG_POWER.vusb_stat.gpio_pin;
GPIO_Init(BOARD_CONFIG_POWER.vusb_stat.gpio, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = BOARD_CONFIG_POWER.chg_stat.gpio_pin;
GPIO_Init(BOARD_CONFIG_POWER.chg_stat.gpio, &GPIO_InitStructure);
if (board_has_chg_fast() || board_has_chg_en()) {
// Initialize PD2 as the sensor enable
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
if (board_has_chg_fast()) {
gpio_use(BOARD_CONFIG_POWER.chg_fast.gpio);
GPIO_InitStructure.GPIO_Pin = BOARD_CONFIG_POWER.chg_fast.gpio_pin;
GPIO_Init(BOARD_CONFIG_POWER.chg_fast.gpio, &GPIO_InitStructure);
prv_battery_set_fast_charge(false);
gpio_release(BOARD_CONFIG_POWER.chg_fast.gpio);
}
if (board_has_chg_en()) {
gpio_use(BOARD_CONFIG_POWER.chg_en.gpio);
GPIO_InitStructure.GPIO_Pin = BOARD_CONFIG_POWER.chg_en.gpio_pin;
GPIO_Init(BOARD_CONFIG_POWER.chg_en.gpio, &GPIO_InitStructure);
prv_battery_set_charge_enable(true);
gpio_release(BOARD_CONFIG_POWER.chg_en.gpio);
}
}
if (BOARD_CONFIG_POWER.has_vusb_interrupt) {
periph_config_release_lock();
exti_configure_pin(BOARD_CONFIG_POWER.vusb_exti, ExtiTrigger_RisingFalling,
battery_vusb_interrupt_handler);
exti_enable(BOARD_CONFIG_POWER.vusb_exti);
periph_config_acquire_lock();
} else {
// TODO: Start polling vusb_stat
}
gpio_release(BOARD_CONFIG_POWER.vusb_stat.gpio);
gpio_release(BOARD_CONFIG_POWER.chg_stat.gpio);
periph_config_release_lock();
if (BOARD_CONFIG_POWER.has_vusb_interrupt) {
// Prime the debounced state.
s_debounced_is_usb_connected = battery_is_usb_connected_raw();
}
}
bool battery_charge_controller_thinks_we_are_charging_impl(void) {
periph_config_acquire_lock();
gpio_use(BOARD_CONFIG_POWER.chg_stat.gpio);
bool state = !GPIO_ReadInputDataBit(BOARD_CONFIG_POWER.chg_stat.gpio, BOARD_CONFIG_POWER.chg_stat.gpio_pin);
gpio_release(BOARD_CONFIG_POWER.chg_stat.gpio);
periph_config_release_lock();
return state;
}
static bool battery_is_usb_connected_raw(void) {
periph_config_acquire_lock();
gpio_use(BOARD_CONFIG_POWER.vusb_stat.gpio);
bool state = !GPIO_ReadInputDataBit(BOARD_CONFIG_POWER.vusb_stat.gpio, BOARD_CONFIG_POWER.vusb_stat.gpio_pin);
gpio_release(BOARD_CONFIG_POWER.vusb_stat.gpio);
periph_config_release_lock();
return state;
}
bool battery_is_usb_connected_impl(void) {
if (BOARD_CONFIG_POWER.has_vusb_interrupt) {
return s_debounced_is_usb_connected;
} else {
return battery_is_usb_connected_raw();
}
}
// This callback gets installed by DBG_SERIAL_FREERTOS_IRQHandler() using system_task_add_callback_from_isr().
// It is used to start up our timer since doing so from an ISR is not allowed.
static void prv_start_timer_sys_task_callback(void* data) {
new_timer_start(s_debounce_timer_handle, USB_CONN_DEBOUNCE_MS, battery_conn_debounce_callback, NULL, 0 /*flags*/);
}
static void battery_vusb_interrupt_handler(bool *should_context_switch) {
// Start the timer from a system task callback - not allowed to do so from an ISR
system_task_add_callback_from_isr(prv_start_timer_sys_task_callback, NULL, should_context_switch);
}
int battery_get_millivolts(void) {
ADCVoltageMonitorReading info = battery_read_voltage_monitor();
// Apologies for the madness numbers.
// The previous implementation had some approximations in it. The battery voltage is scaled
// down by a pair of resistors (750k at the top, 470k at the bottom), resulting in a required
// scaling of (75 + 47) / 47 or roughly 2.56x, but the previous implementation also required
// fudging the numbers a bit in order to approximate for leakage current (a 73/64 multiple
// was arbitrarily increased to 295/256). In order to match this previous arbitrary scaling
// I've chosen new numbers that provide 2.62x scaling, which is the previous 2.56x with the
// same amount of fudging applied.
return battery_convert_reading_to_millivolts(info, 3599, 1373);
}
extern void command_sim_battery_connection(const char *bool_str) {
bool value = atoi(bool_str);
PebbleEvent event = {
.type = PEBBLE_BATTERY_CONNECTION_EVENT,
.battery_connection = {
.is_connected = value,
}
};
event_put(&event);
}
void battery_set_charge_enable(bool charging_enabled) {
periph_config_acquire_lock();
prv_battery_set_charge_enable(charging_enabled);
periph_config_release_lock();
}
void battery_set_fast_charge(bool fast_charge_enabled) {
periph_config_acquire_lock();
prv_battery_set_fast_charge(fast_charge_enabled);
periph_config_release_lock();
}

114
src/fw/drivers/button.c Normal file
View file

@ -0,0 +1,114 @@
/*
* 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 "console/prompt.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 (BOARD_CONFIG_BUTTON.active_high) ? bit : !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(SYSCFG, RCC_APB2Periph_SYSCFG);
initialize_button_common();
for (int i = 0; i < NUM_BUTTONS; ++i) {
initialize_button(&BOARD_CONFIG_BUTTON.buttons[i]);
}
periph_config_disable(SYSCFG, RCC_APB2Periph_SYSCFG);
periph_config_release_lock();
}
bool button_selftest(void) {
return button_get_state_bits() == 0;
}
void command_button_read(const char* button_id_str) {
int button = atoi(button_id_str);
if (button < 0 || button >= NUM_BUTTONS) {
prompt_send_response("Invalid button");
return;
}
if (button_is_pressed(button)) {
prompt_send_response("down");
} else {
prompt_send_response("up");
}
}

29
src/fw/drivers/button.h Normal file
View file

@ -0,0 +1,29 @@
/*
* 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.
*/
#pragma once
#include "button_id.h"
#include <stdbool.h>
#include <stdint.h>
void button_init(void);
bool button_is_pressed(ButtonId id);
uint8_t button_get_state_bits(void);
bool button_selftest(void);

View file

@ -0,0 +1,41 @@
/*
* 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.
*/
#pragma once
//! @addtogroup UI
//! @{
//! @addtogroup Clicks
//! \brief Dealing with button input
//! @{
//! Button ID values
//! @see \ref click_recognizer_get_button_id()
typedef enum {
//! Back button
BUTTON_ID_BACK = 0,
//! Up button
BUTTON_ID_UP,
//! Select (middle) button
BUTTON_ID_SELECT,
//! Down button
BUTTON_ID_DOWN,
//! Total number of buttons
NUM_BUTTONS
} ButtonId;
//! @} // end addtogroup Clicks
//! @} // end addtogroup UI

View file

@ -0,0 +1,31 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
//! Configure and start the 32 kHz LSE clock.
void clocksource_lse_configure(void);
//! Returns true iff LSE is running.
bool clocksource_is_lse_started(void);
//! Enable or disable 32 kHz clock output on pin MCO1.
//!
//! Prerequisite: clocksource_lse_configure() must be called beforehand to
//! enable the 32 kHz clock.
void clocksource_MCO1_enable(bool on);

View file

@ -0,0 +1,270 @@
/*
* 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/debounced_button.h"
#include "board/board.h"
#include "drivers/button.h"
#include "drivers/exti.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/timer.h"
#include "kernel/events.h"
#include "kernel/util/stop.h"
#include "system/bootbits.h"
#include "system/reset.h"
#include "util/bitset.h"
#include "kernel/util/sleep.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#include "projdefs.h"
// We want TIM4 to run at 32KHz
static const uint32_t TIMER_FREQUENCY_HZ = 32000;
// Sample the buttons every 2ms to debounce
static const uint32_t TIMER_PERIOD_TICKS = 64;
// A button must be stable for 20 samples (40ms) to be accepted.
static const uint32_t NUM_DEBOUNCE_SAMPLES = 20;
#define RESET_BUTTONS ((1 << BUTTON_ID_SELECT) | (1 << BUTTON_ID_BACK))
#define DEBOUNCE_SAMPLES_PER_SECOND (TIMER_FREQUENCY_HZ / TIMER_PERIOD_TICKS)
// This reset-buttons-held timeout must be lower than the PMIC's back-button-reset timeout,
// which is ~8-11s. The spacing between these timeouts should be large enough to avoid accidentally
// shutting down the device when a customer is attempting to reset. Therefore the FW's
// reset-buttons-held timeout is set to 5 seconds:
#define RESET_THRESHOLD_SAMPLES (5 * DEBOUNCE_SAMPLES_PER_SECOND)
static void initialize_button_timer(void) {
periph_config_enable(TIM4, RCC_APB1Periph_TIM4);
NVIC_InitTypeDef NVIC_InitStructure;
/* Enable the TIM4 gloabal Interrupt */
TIM_ClearITPendingBit(TIM4, TIM_IT_Update);
NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0b;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
TIM_TimeBaseInitTypeDef tim_config;
TIM_TimeBaseStructInit(&tim_config);
tim_config.TIM_Period = TIMER_PERIOD_TICKS;
// The timer is on ABP1 which is clocked by PCLK1
TimerConfig tc = {
.peripheral = TIM4,
.config_clock = RCC_APB1Periph_TIM4,
};
tim_config.TIM_Prescaler = timer_find_prescaler(&tc,
TIMER_FREQUENCY_HZ);
tim_config.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(TIM4, &tim_config);
periph_config_disable(TIM4, RCC_APB1Periph_TIM4);
}
static bool prv_check_timer_enabled(void) {
// We're only enabled if all the configuration is correct.
return (TIM4->CR1 & TIM_CR1_CEN) && // TIM_Cmd
(TIM4->DIER & TIM_IT_Update) && // TIM_ITConfig
(RCC->APB1ENR & RCC_APB1Periph_TIM4); // RCC_APB1PeriphClockCmd
}
static void disable_button_timer(void) {
if (prv_check_timer_enabled()) {
TIM_Cmd(TIM4, DISABLE);
TIM_ITConfig(TIM4, TIM_IT_Update, DISABLE);
periph_config_disable(TIM4, RCC_APB1Periph_TIM4);
// Allow us to enter stop mode
stop_mode_enable(InhibitorButton);
}
}
static void prv_enable_button_timer(void) {
// Don't let the timer interrupt us while we're mucking with it.
__disable_irq();
if (!prv_check_timer_enabled()) {
periph_config_enable(TIM4, RCC_APB1Periph_TIM4);
TIM_ITConfig(TIM4, TIM_IT_Update, ENABLE);
TIM_Cmd(TIM4, ENABLE);
// Prevent us from entering stop mode (and disabling the clock timer)
stop_mode_disable(InhibitorButton);
}
__enable_irq();
}
static void prv_button_interrupt_handler(bool *should_context_switch) {
prv_enable_button_timer();
}
static void clear_stuck_button(ButtonId button_id) {
__disable_irq();
const uint32_t button_counter_register = RTC_ReadBackupRegister(STUCK_BUTTON_REGISTER);
if (button_counter_register != 0) {
// Create bitmask with all 1s, except on the counter byte for this button_id in button_counter_register. AND to mask out:
const uint32_t updated_button_counter_register = button_counter_register & ~(0xff << (button_id << 3));
if (button_counter_register != updated_button_counter_register) {
RTC_WriteBackupRegister(STUCK_BUTTON_REGISTER, updated_button_counter_register);
}
}
__enable_irq();
}
void debounced_button_init(void) {
button_init();
#if defined(BOARD_SNOWY_BB2) || defined(BOARD_SPALDING_BB2)
// Snowy BB2s have a capacitor that results in a really slow rise time (~0.4ms). Sleep for
// at least 1 ms to prevent fake button events
psleep(2);
#endif
for (int i = 0; i < NUM_BUTTONS; ++i) {
const ExtiConfig config = BOARD_CONFIG_BUTTON.buttons[i].exti;
exti_configure_pin(config, ExtiTrigger_RisingFalling, prv_button_interrupt_handler);
exti_enable(config);
}
initialize_button_timer();
// If someone is holding down a button, we need to start up the timer immediately ourselves as
// we won't get a button down interrupt to start it.
if (button_get_state_bits() != 0) {
prv_enable_button_timer();
}
}
// Interrupt Service Routines
///////////////////////////////////////////////////////////
void TIM4_IRQHandler(void) {
// This array holds the number of samples we have for the button being in a different state than
// the current debounced state of the button.
static uint32_t s_button_timers[] = {0, 0, 0, 0};
// A bitset of the current states of the buttons after the debouncing is done.
static uint32_t s_debounced_button_state = 0;
// Should we tell the scheduler to attempt to context switch after this function has completed?
bool should_context_switch = pdFALSE;
// Should we power down this interrupt timer once we're done here or should we leave it on?
bool can_power_down_tim4 = true;
// We handle all 4 buttons every time this interrupt is fired.
for (int i = 0; i < NUM_BUTTONS; ++i) {
// What stable state is the button in, according to the debouncing algorithm?
bool debounced_button_state = bitset32_get(&s_debounced_button_state, i);
// What is the current physical state of the button?
bool is_pressed = button_is_pressed(i);
if (is_pressed == debounced_button_state) {
// If the state is not changing, skip this button.
s_button_timers[i] = 0;
continue;
}
// Leave the timer running so we can track this button that's changing state.
can_power_down_tim4 = false;
s_button_timers[i] += 1;
// If the button has been in a stable state that's different than the debounced state for enough
// samples, change the debounced state to the stable state and generate an event.
if (s_button_timers[i] == NUM_DEBOUNCE_SAMPLES) {
s_button_timers[i] = 0;
bitset32_update(&s_debounced_button_state, i, is_pressed);
if (!is_pressed) {
// A button has been released. Make sure we weren't tracking this as a stuck button.
clear_stuck_button(i);
}
PebbleEvent e = {
.type = (is_pressed) ? PEBBLE_BUTTON_DOWN_EVENT : PEBBLE_BUTTON_UP_EVENT,
.button.button_id = i
};
should_context_switch = event_put_isr(&e);
}
}
#if !defined(MANUFACTURING_FW)
// Now that s_debounced_button_state is updated, check to see if the user is holding down the reset
// combination.
static uint32_t s_hard_reset_timer = 0;
if ((s_debounced_button_state & RESET_BUTTONS) == RESET_BUTTONS) {
s_hard_reset_timer += 1;
can_power_down_tim4 = false;
if (s_hard_reset_timer > RESET_THRESHOLD_SAMPLES) {
__disable_irq();
// If the UP button is held at the moment the timeout is hit, set the force-PRF bootbit:
const bool force_prf = (s_debounced_button_state & (1 << BUTTON_ID_UP));
if (force_prf) {
boot_bit_set(BOOT_BIT_FORCE_PRF);
}
RebootReason reason = {
.code = force_prf ? RebootReasonCode_PrfResetButtonsHeld :
RebootReasonCode_ResetButtonsHeld
};
reboot_reason_set(&reason);
// Don't use system_reset here. This back door absolutely must work. Just hard reset.
system_hard_reset();
}
} else {
s_hard_reset_timer = 0;
}
#endif
if (can_power_down_tim4) {
__disable_irq();
disable_button_timer();
__enable_irq();
}
TIM_ClearITPendingBit(TIM4, TIM_IT_Update);
portEND_SWITCHING_ISR(should_context_switch);
}
// Serial commands
///////////////////////////////////////////////////////////
void command_put_raw_button_event(const char* button_index, const char* is_button_down_event) {
PebbleEvent e;
int is_down = atoi(is_button_down_event);
int button = atoi(button_index);
if ((button < 0 || button > NUM_BUTTONS) || (is_down != 1 && is_down != 0)) {
return;
}
e.type = (is_down) ? PEBBLE_BUTTON_DOWN_EVENT : PEBBLE_BUTTON_UP_EVENT;
e.button.button_id = button;
event_put(&e);
}

View file

@ -0,0 +1,20 @@
/*
* 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.
*/
#pragma once
void debounced_button_init(void);

View file

@ -0,0 +1,56 @@
/*
* 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.
*/
#pragma once
#include "board/display.h"
#include <stdint.h>
#include <stdbool.h>
typedef struct {
uint8_t address;
uint8_t* data;
} DisplayRow;
typedef bool(*NextRowCallback)(DisplayRow* row);
typedef void(*UpdateCompleteCallback)(void);
//! Show the splash screen before the display has been fully initialized.
void display_show_splash_screen(void);
void display_init(void);
uint32_t display_baud_rate_change(uint32_t new_frequency_hz);
void display_clear(void);
void display_update(NextRowCallback nrcb, UpdateCompleteCallback uccb);
bool display_update_in_progress(void);
void display_pulse_vcom(void);
//! Show the panic screen.
//!
//! This function is only defined if the display hardware and driver support it.
void display_show_panic_screen(uint32_t error_code);
typedef struct GPoint GPoint;
void display_set_offset(GPoint offset);
GPoint display_get_offset(void);

View file

@ -0,0 +1,602 @@
/*
* 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/display/ice40lp/ice40lp.h"
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "FreeRTOS.h"
#include "applib/graphics/framebuffer.h"
#include "applib/graphics/gtypes.h"
#include "board/board.h"
#include "board/display.h"
#include "debug/power_tracking.h"
#include "drivers/clocksource.h"
#include "drivers/display/ice40lp/fpga_bitstream.auto.h"
#include "drivers/display/ice40lp/ice40lp_definitions.h"
#include "drivers/display/ice40lp/ice40lp_internal.h"
#include "drivers/display/ice40lp/snowy_boot.h"
#include "drivers/dma.h"
#include "drivers/exti.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/pmic.h"
#include "drivers/spi.h"
#include "drivers/spi_dma.h"
#include "kernel/events.h"
#include "kernel/event_loop.h"
#include "kernel/util/sleep.h"
#include "kernel/util/stop.h"
#include "os/mutex.h"
#include "os/tick.h"
#include "semphr.h"
#include "services/common/analytics/analytics.h"
#include "services/common/compositor/compositor.h"
#include "services/common/compositor/compositor_display.h"
#include "services/common/system_task.h"
#include "system/logging.h"
#include "system/passert.h"
#include "system/profiler.h"
#include "task.h"
#include "util/attributes.h"
#include "util/net.h"
#include "util/reverse.h"
#include "util/size.h"
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#if DISPLAY_ORIENTATION_ROW_MAJOR || DISPLAY_ORIENTATION_ROW_MAJOR_INVERTED
#define DISP_LINES DISP_ROWS
#define DISP_PIXELS DISP_COLS
#elif DISPLAY_ORIENTATION_COLUMN_MAJOR_INVERTED
#define DISP_LINES DISP_COLS
#define DISP_PIXELS DISP_ROWS
#else
#error "Unknown or missing display orientation define"
#endif
typedef void (*PopulateLineCB)(
int column, uint8_t * restrict line_buffer, const void *cb_data);
//! 2 buffers to hold line data being transferred.
static uint8_t DMA_READ_BSS s_line_buffer[2][DISP_PIXELS];
//! buffer index keeps track of which line buffer is in use
static uint32_t s_buffer_idx;
//! line index is the line of the display currently being updated
static uint32_t s_line_index;
//! offset for shifting the image origin from the display's origin
//! display coordinates (0,0) are top-left,
//! offset positive values shift right and down
static GPoint s_disp_offset;
static bool s_update_in_progress;
static bool s_terminate_pending;
static RtcTicks s_start_ticks;
static bool s_initialized = false;
//! lockout to prevent display updates when the panic screen is shown
static bool s_panic_screen_lockout;
static PebbleMutex *s_display_update_mutex;
static SemaphoreHandle_t s_fpga_busy;
static UpdateCompleteCallback s_update_complete_callback;
static void prv_start_dma_transfer(uint8_t *addr, uint32_t length);
static void display_interrupt_intn(bool *should_context_switch);
static inline OPTIMIZE_FUNC(2) void prv_pixel_scramble(
uint8_t * restrict line_buf, const uint8_t px_odd, const uint8_t px_even,
const int offset) {
uint8_t msb, lsb;
msb = (px_odd & 0b00101010) | (px_even & 0b00101010) >> 1;
lsb = (px_odd & 0b00010101) << 1 | (px_even & 0b00010101);
line_buf[offset/2] = msb;
line_buf[offset/2 + DISP_PIXELS/2] = lsb;
}
static inline OPTIMIZE_FUNC(2) void prv_row_major_get_line(
uint8_t * restrict line, const uint8_t * restrict image_buf,
int index) {
#if DISPLAY_ORIENTATION_ROW_MAJOR_INVERTED
// Optimized line renderer for Robert.
// Could easily apply to the other screens, but only Robert really needs it.
// By loading both pixels with a single load, we can cut down code size (cache benefit)
// and decrease number of bus accesses.
// Theoretically loading 4 pixels at a time should be better, but GCC generated much
// worse code that way.
#if DISPLAY_ORIENTATION_ROTATED_180
// Setup srcbuf to be the end, since we need to scan backwards horizontally
const uint16_t *srcbuf = (const uint16_t *)(image_buf + DISP_PIXELS * index);
for (int dst_offset = 0; dst_offset < DISP_PIXELS/2; dst_offset++) {
// Get the two pixels
const uint16_t pix = *srcbuf++;
// Swizzle the pixels
line[0] = ((pix) & 0b101010) | ((pix >> 9) & 0b010101);
line[DISP_PIXELS/2] = ((pix << 1) & 0b101010) | ((pix >> 8) & 0b010101);
line++;
}
#else
// Setup srcbuf to be the end, since we need to scan backwards horizontally
const uint16_t *srcbuf = (const uint16_t *)(image_buf + DISP_PIXELS * (DISP_LINES - index) - 2);
for (int dst_offset = 0; dst_offset < DISP_PIXELS/2; dst_offset++) {
// Get the two pixels
const uint16_t pix = *srcbuf--;
// Swizzle the pixels
line[0] = ((pix >> 8) & 0b101010) | ((pix >> 1) & 0b010101);
line[DISP_PIXELS/2] = ((pix >> 7) & 0b101010) | ((pix) & 0b010101);
line++;
}
#endif // DISPLAY_ORIENTATION_ROTATED_180
#else
// adjust line index according to display offset,
// populate blank (black) line if this exceeds the source framebuffer
index -= s_disp_offset.y;
if (!WITHIN(index, 0, DISP_LINES - 1)) {
memset(line, 0, DISP_PIXELS);
return;
}
uint8_t odd, even;
#if PLATFORM_SPALDING
const GBitmapDataRowInfoInternal *row_infos = g_gbitmap_spalding_data_row_infos;
const uint8_t *row_start = image_buf + row_infos[index].offset;
#endif
// Line starts with MSB of each color in all pixels
// Line finishes with LSB of each color in all pixels
// separate src_offset is adjusted according to manufacturing offset,
// loop condition/continue makes sure we don't read past boundaries of src framebuffer
for (int src_offset = -s_disp_offset.x, dst_offset = 0;
src_offset < DISP_PIXELS && dst_offset < DISP_PIXELS;
src_offset += 2, dst_offset += 2) {
#if !PLATFORM_SPALDING
if (src_offset < 0) {
continue;
}
#endif
#if DISPLAY_ORIENTATION_ROW_MAJOR
#if PLATFORM_SPALDING
even = WITHIN(src_offset + 1, row_infos[index].min_x, row_infos[index].max_x) ?
row_start[src_offset + 1] : 0;
odd = WITHIN(src_offset, row_infos[index].min_x, row_infos[index].max_x) ?
row_start[src_offset] : 0;
#else
#error Unsupported display
#endif
#elif DISPLAY_ORIENTATION_COLUMN_MAJOR_INVERTED
even = image_buf[DISP_COLS * (DISP_ROWS-2 - src_offset) + index];
odd = image_buf[DISP_COLS * (DISP_ROWS-2 - src_offset + 1) + index];
#endif
prv_pixel_scramble(line, odd, even, dst_offset);
}
#endif
}
static void prv_framebuffer_populate_line(
int index, uint8_t * restrict line) {
const uint8_t *frame_buffer = compositor_get_framebuffer()->buffer;
prv_row_major_get_line(line, frame_buffer, index);
}
static void enable_display_dma_clock(void) {
power_tracking_start(PowerSystemMcuDma2);
}
static void disable_display_dma(void) {
// Properly disable DMA interrupts and deinitialize the DMA controller to prevent pending
// interrupts from firing when the clock is re-enabled (this could possibly cause a stray
// terminate callback being added to kernel main)
spi_ll_slave_write_dma_stop(ICE40LP->spi_port);
power_tracking_stop(PowerSystemMcuDma2);
}
static void prv_terminate_transfer(void *data) {
if (s_panic_screen_lockout) {
return;
}
// Only need intn when communicating with the display.
// Disable EXTI interrupt before ending the frame to prevent possible race condition resulting
// from a almost empty FIFO on the FPGA triggering a terminate call before the interrupt is
// disabled
exti_disable(ICE40LP->busy_exti);
disable_display_dma();
display_spi_end_transaction();
analytics_stopwatch_stop(ANALYTICS_APP_METRIC_DISPLAY_WRITE_TIME);
s_update_in_progress = false;
s_terminate_pending = false;
mutex_unlock(s_display_update_mutex);
// Store temporary variable, then NULL, to protect against the case where the compositor calls
// into the display driver from the callback, then we NULL out the update complete callback
// afterwards.
UpdateCompleteCallback update_complete_cb = s_update_complete_callback;
s_update_complete_callback = NULL;
if (update_complete_cb) {
update_complete_cb();
}
}
static uint32_t prv_get_next_buffer_idx(uint32_t idx) {
return (idx + 1) % ARRAY_LENGTH(s_line_buffer);
}
//! Wait for the FPGA to finish updating the display.
//! @returns true if the FPGA is busy on exit
static bool prv_wait_busy(void) {
// Make sure that semaphore token count is zero before we wait on it and before we check the state
// of the FPGA busy line to prevent the semaphore take/give from getting out of sync (not exactly
// sure what race condition causes the out of sync bug, but it seems to happen after a while).
// See https://pebbletechnology.atlassian.net/browse/PBL-21904
xSemaphoreTake(s_fpga_busy, 0);
if (!display_busy()) {
return false;
}
// A full frame should take no longer than 33 msec to draw. If we are waiting
// longer than that, something is very wrong.
TickType_t max_wait_time_ticks = milliseconds_to_ticks(40);
bool busy_on_exit = false;
if (xSemaphoreTake(s_fpga_busy, max_wait_time_ticks) != pdTRUE) {
PBL_LOG(LOG_LEVEL_ERROR, "Display not coming out of a busy state.");
// Nothing needs to be done to recover the FPGA from a bad state. The
// falling edge of SCS (to start a new frame) resets the FPGA logic,
// clearing the error state.
busy_on_exit = true;
}
return busy_on_exit;
}
static void prv_reprogram_display(void) {
// CDONE is expected to go low during reprogramming. Don't pollute the logs
// with "CDONE has gone low" messages.
analytics_inc(ANALYTICS_DEVICE_METRIC_FPGA_REPROGRAM_COUNT,
AnalyticsClient_System);
exti_disable(ICE40LP->cdone_exti);
display_program(s_fpga_bitstream, sizeof(s_fpga_bitstream));
exti_enable(ICE40LP->cdone_exti);
}
static void prv_cdone_low_handler(void *context) {
PBL_LOG(LOG_LEVEL_ERROR,
"CDONE has gone low. The FPGA has lost its configuration.");
if (!mutex_lock_with_timeout(s_display_update_mutex, 200)) {
PBL_LOG(LOG_LEVEL_DEBUG,
"Couldn't lock out display driver to reprogram FPGA.");
return;
}
prv_reprogram_display();
PBL_ASSERTN(!display_busy());
mutex_unlock(s_display_update_mutex);
}
static void prv_cdone_low_isr(bool *should_context_switch) {
system_task_add_callback_from_isr(prv_cdone_low_handler, NULL,
should_context_switch);
}
void display_init(void) {
if (s_initialized) {
return;
}
clocksource_MCO1_enable(true);
s_panic_screen_lockout = false;
s_display_update_mutex = mutex_create();
s_fpga_busy = xSemaphoreCreateBinary();
s_update_in_progress = false;
s_terminate_pending = false;
s_update_complete_callback = NULL;
display_start();
display_program(s_fpga_bitstream, sizeof(s_fpga_bitstream));
// enable the power rails
display_power_enable();
// Set up our INT_N interrupt, aka the "busy line" from the FPGA
exti_configure_pin(ICE40LP->busy_exti, ExtiTrigger_Falling, display_interrupt_intn);
// Set up an interrupt to detect the FPGA forgetting its configuration due to
// e.g. an ESD event.
exti_configure_pin(ICE40LP->cdone_exti, ExtiTrigger_Falling, prv_cdone_low_isr);
exti_enable(ICE40LP->cdone_exti);
s_initialized = true;
}
bool display_update_in_progress(void) {
// Set this timeout to a relatively large value so that we don't unlock the mutex too early when
// the DMA controller that is used by the display is being heavily used by another driver (e.g.
// the bluetooth HCI port) and delays the completion of the update or kernel_main is busy with
// other tasks (e.g. voice encoding).
// (see https://pebbletechnology.atlassian.net/browse/PBL-21923)
static const RtcTicks MAX_BUSY_TICKS = 200;
bool in_progress = !mutex_lock_with_timeout(s_display_update_mutex, 0);
if (!in_progress) {
mutex_unlock(s_display_update_mutex);
} else if (!s_panic_screen_lockout) {
if ((rtc_get_ticks() - s_start_ticks) > MAX_BUSY_TICKS) {
// Ensure that terminate transfer is not enqueued on kernel_main twice when it is busy to
// prevent terminate transfer from being invoked twice
// see https://pebbletechnology.atlassian.net/browse/PBL-22084
// Read and set the termination flag in a critical section to prevent an interrupt pending
// a transfer if these events occur simultaneously
bool pend_terminate = false;
portENTER_CRITICAL();
if (!s_terminate_pending) {
s_terminate_pending = true;
pend_terminate = true;
}
portEXIT_CRITICAL();
if (pend_terminate) {
PROFILER_NODE_STOP(display_transfer);
launcher_task_add_callback(prv_terminate_transfer, NULL);
}
}
}
return in_progress;
}
static void prv_do_display_update(void) {
if (!mutex_lock_with_timeout(s_display_update_mutex, 0)) {
PBL_LOG(LOG_LEVEL_DEBUG, "Couldn't start update.");
return;
}
if (s_panic_screen_lockout) {
mutex_unlock(s_display_update_mutex);
return;
}
analytics_stopwatch_start(ANALYTICS_APP_METRIC_DISPLAY_WRITE_TIME, PebbleTask_App);
analytics_inc(ANALYTICS_DEVICE_METRIC_DISPLAY_UPDATES_PER_HOUR, AnalyticsClient_System);
// Communicating with the display, need intn.
exti_enable(ICE40LP->busy_exti);
enable_display_dma_clock();
// Send the first line...
prv_framebuffer_populate_line(0, s_line_buffer[s_buffer_idx]);
prv_wait_busy();
display_spi_begin_transaction();
display_start_frame();
if (display_busy()) {
// If the FPGA was stuck busy before, starting the frame (SCS falling edge)
// should get it unstuck. If BUSY is still asserted, the FPGA might be
// unprogrammed or malfunctioning. Either way, reprogramming it should get
// it back into working order.
PBL_LOG(LOG_LEVEL_WARNING,
"Reprogramming FPGA because busy is stuck asserted");
prv_reprogram_display();
bool is_busy = display_busy();
#ifdef TARGET_QEMU
// Bold light-red text on a black background
#define M(s) PBL_LOG(LOG_LEVEL_ALWAYS, "\033[1;91;40m" s "\033[0m")
if (is_busy) {
M("################################################");
M("# THIS IS A QEMU BUILD #");
M("################################################");
M("# #");
M("# The QEMU display driver \033[1;4mdoes not work\033[24m on #");
M("# physical hardware. You must build without #");
M("# the --qemu switch when flashing a bigboard. #");
M("################################################");
#undef M
psleep(3000);
}
#endif
PBL_ASSERTN(!is_busy);
// The SPI clock is disabled by prv_reprogram_display.
display_spi_begin_transaction();
display_start_frame();
}
// set line index after waiting for display to free up
uint32_t current_idx = s_buffer_idx;
s_buffer_idx = prv_get_next_buffer_idx(s_buffer_idx);
// populate the second line and set the next line to be processed as the third line
prv_framebuffer_populate_line(1, s_line_buffer[s_buffer_idx]);
s_line_index = 2;
stop_mode_disable(InhibitorDisplay);
PROFILER_NODE_START(display_transfer);
s_update_in_progress = true;
s_start_ticks = rtc_get_ticks();
// Start the DMA last to prevent possible race conditions caused by unfortunately timed context
// switch
prv_start_dma_transfer(s_line_buffer[current_idx], DISP_PIXELS);
}
//!
//! Starts a redraw of the entire framebuffer to the screen.
//!
//! Currently does NOT:
//! - make use of nrcb due to rotation requirements; instead accesses the framebuffer directly
//! - support partial screen updates
//!
void display_update(NextRowCallback nrcb, UpdateCompleteCallback uccb) {
PBL_ASSERTN(uccb != NULL);
s_update_complete_callback = uccb;
prv_do_display_update();
}
static void prv_do_display_update_cb(void *ignored) {
prv_do_display_update();
}
void display_clear(void) {
// Set compositor buffer to the powered off color (black) and redraw.
// Note that compositor owns this framebuffer!
memset(compositor_get_framebuffer()->buffer, 0x00, FRAMEBUFFER_SIZE_BYTES);
// The display ISRs pend events on KernelMain and thus implicitly assume
// that the display update operation began on KernelMain. If we are already
// running on KernelMain, then just run the display update, otherwise schedule
// a callback to run on KernelMain that performs the update
if (pebble_task_get_current() == PebbleTask_KernelMain) {
prv_do_display_update();
} else {
launcher_task_add_callback(prv_do_display_update_cb, NULL);
}
}
void display_pulse_vcom(void) { }
//! @return false if there are no more lines to transfer, true if a new line transfer was started
static bool prv_write_next_line(bool *should_context_switch) {
if (s_line_index == 0 && (!s_terminate_pending)) {
s_terminate_pending = true;
PROFILER_NODE_STOP(display_transfer);
PebbleEvent e = {
.type = PEBBLE_CALLBACK_EVENT,
.callback = {
.callback = prv_terminate_transfer,
},
};
*should_context_switch = event_put_isr(&e);
return false;
}
prv_start_dma_transfer(s_line_buffer[s_buffer_idx], DISP_PIXELS);
if (s_line_index < DISP_LINES) {
s_buffer_idx = prv_get_next_buffer_idx(s_buffer_idx);
prv_framebuffer_populate_line(s_line_index, s_line_buffer[s_buffer_idx]);
s_line_index++;
} else {
// done
s_line_index = 0;
}
return true;
}
//! When the FPGA leaves the busy state while frame data is being sent, this interrupt will
//! signal that the next line can be sent to the display.
static void display_interrupt_intn(bool *should_context_switch) {
if (s_update_in_progress) {
if (!spi_ll_slave_dma_in_progress(ICE40LP->spi_port)) {
// DMA transfer is complete
if (prv_write_next_line(should_context_switch)) {
stop_mode_disable(InhibitorDisplay);
}
}
} else {
// Only release the semaphore after the end of an update
signed portBASE_TYPE was_higher_priority_task_woken = pdFALSE;
xSemaphoreGiveFromISR(s_fpga_busy, &was_higher_priority_task_woken);
*should_context_switch = (*should_context_switch) ||
(was_higher_priority_task_woken != pdFALSE);
}
}
// DMA
//////////////////
//! This interrupt fires when the transfer of a line has completed.
static bool prv_write_dma_irq_handler(const SPISlavePort *request, void *context) {
PROFILER_NODE_START(framebuffer_dma);
bool should_context_switch = false;
if (display_busy() || !prv_write_next_line(&should_context_switch)) {
stop_mode_enable(InhibitorDisplay);
}
PROFILER_NODE_STOP(framebuffer_dma);
return should_context_switch;
}
static void prv_start_dma_transfer(uint8_t *addr, uint32_t length) {
spi_ll_slave_write_dma_start(ICE40LP->spi_port, addr, length, prv_write_dma_irq_handler, NULL);
}
void display_show_panic_screen(uint32_t error_code) {
// Lock out display driver from performing further updates
if (!mutex_lock_with_timeout(s_display_update_mutex, 200)) {
PBL_LOG(LOG_LEVEL_DEBUG, "Couldn't lock out display driver.");
return;
}
s_panic_screen_lockout = true;
exti_disable(ICE40LP->cdone_exti);
// Work around an issue which some boards exhibit where there is about a 50%
// probability that FPGA malfunctions and draw-scene command doesn't work.
// This can be detected in software as the FPGA asserts BUSY indefinitely.
int retries;
for (retries = 0; retries <= 20; ++retries) {
if (!display_switch_to_bootloader_mode()) {
// Probably an unconfigured FPGA. Nothing we can do about that.
break;
}
if (boot_display_show_error_code(error_code)) {
// Success!
if (retries > 0) {
PBL_LOG(LOG_LEVEL_WARNING, "Took %d retries to display panic screen.",
retries);
}
break;
}
}
exti_enable(ICE40LP->cdone_exti);
mutex_unlock(s_display_update_mutex);
}
void display_show_splash_screen(void) {
// Assumes that the FPGA is already in bootloader mode but the SPI peripheral
// and GPIOs are not yet configured; exactly the state that the system is
// expected to be in before display_init() is called.
display_start();
display_spi_configure_default();
boot_display_show_boot_splash();
}
void display_set_offset(GPoint offset) {
s_disp_offset = offset;
}
GPoint display_get_offset(void) {
return s_disp_offset;
}
void analytics_external_collect_display_offset(void) {
analytics_set(ANALYTICS_DEVICE_METRIC_DISPLAY_OFFSET_X, s_disp_offset.x, AnalyticsClient_System);
analytics_set(ANALYTICS_DEVICE_METRIC_DISPLAY_OFFSET_Y, s_disp_offset.y, AnalyticsClient_System);
}

View file

@ -0,0 +1,35 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
#include "../display.h"
typedef enum {
DISP_COLOR_BLACK = 0,
DISP_COLOR_WHITE,
DISP_COLOR_RED,
DISP_COLOR_GREEN,
DISP_COLOR_BLUE,
DISP_COLOR_MAX
} DispColor;
static const uint8_t s_display_colors[DISP_COLOR_MAX] = { 0x00, 0xff, 0xc0, 0x30, 0x0c };
void display_fill_color(uint8_t color_value);
void display_fill_stripes();

View file

@ -0,0 +1,43 @@
/*
* 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.
*/
#pragma once
#include "board/board.h"
#include <stdbool.h>
#include <stdint.h>
// TODO: Calling this ICE40LP kind of sucks, but I can't think of anything better without doing a
// whole big display system refactor, so we're keeping it as ICE40LP.
typedef struct ICE40LPDeviceState {
} ICE40LPDeviceState;
typedef const struct ICE40LPDevice {
ICE40LPDeviceState *state;
SPISlavePort *spi_port;
uint32_t base_spi_frequency;
uint32_t fast_spi_frequency;
const OutputConfig creset;
const InputConfig cdone;
const InputConfig busy;
const ExtiConfig cdone_exti;
const ExtiConfig busy_exti;
bool use_6v6_rail;
} ICE40LPDevice;

View file

@ -0,0 +1,241 @@
/*
* 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/display/ice40lp/ice40lp_internal.h"
#include "board/board.h"
#include "debug/power_tracking.h"
#include "drivers/display/ice40lp/ice40lp_definitions.h"
#include "drivers/periph_config.h"
#include "drivers/gpio.h"
#include "drivers/spi.h"
#include "drivers/exti.h"
#include "drivers/pmic.h"
#include "system/logging.h"
#include "system/passert.h"
#include "kernel/util/delay.h"
#include "util/size.h"
#include "util/sle.h"
#include "kernel/util/sleep.h"
#include "util/units.h"
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#include <string.h>
bool display_busy(void) {
return gpio_input_read(&ICE40LP->busy);
}
void display_spi_begin_transaction(void) {
spi_ll_slave_acquire(ICE40LP->spi_port);
spi_ll_slave_scs_assert(ICE40LP->spi_port);
power_tracking_start(PowerSystemMcuSpi6);
}
void display_spi_end_transaction(void) {
spi_ll_slave_scs_deassert(ICE40LP->spi_port);
spi_ll_slave_release(ICE40LP->spi_port);
power_tracking_stop(PowerSystemMcuSpi6);
}
// Temporary code to support prv_do_display_update() logic that attempts to use the
// bootloader error display
void display_spi_configure_default(void) {
spi_slave_set_frequency(ICE40LP->spi_port, ICE40LP->base_spi_frequency);
}
void display_start() {
periph_config_acquire_lock();
gpio_output_init(&ICE40LP->creset, GPIO_OType_OD, GPIO_Speed_25MHz);
gpio_input_init(&ICE40LP->cdone);
gpio_input_init(&ICE40LP->busy);
periph_config_release_lock();
}
static bool prv_spin_until_creset_is(bool level) {
int timeout_us = 500 * 1000;
InputConfig creset_input = {
.gpio = ICE40LP->creset.gpio,
.gpio_pin = ICE40LP->creset.gpio_pin,
};
while (timeout_us > 0) {
if (gpio_input_read(&creset_input) == level) return true;
delay_us(100);
timeout_us -= 100;
}
return false;
}
static bool prv_wait_programmed(void) {
// The datasheet lists the typical NVCM configuration time as 56 ms.
// Something is wrong if it takes more than twice that time.
int timeout = 100 * 10; // * 100 microseconds
while (!gpio_input_read(&ICE40LP->cdone)) {
if (timeout-- == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "FPGA CDONE timeout expired!");
return false;
}
delay_us(100);
}
return true;
}
static bool prv_try_program(const uint8_t *fpga_bitstream,
uint32_t bitstream_size) {
display_spi_configure_default();
spi_ll_slave_acquire(ICE40LP->spi_port);
spi_ll_slave_scs_assert(ICE40LP->spi_port);
gpio_output_set(&ICE40LP->creset, false); // CRESET LOW
#if !defined(TARGET_QEMU)
// Wait until we succeed in pulling CRESET down against the external pull-up
// and other external circuitry which is fighting against us.
PBL_ASSERT(prv_spin_until_creset_is(false), "CRESET not low during reset");
// CRESET needs to be low for 200 ns to actually reset the FPGA.
delay_us(10);
#endif
gpio_output_set(&ICE40LP->creset, true); // CRESET -> HIGH
#if !defined(TARGET_QEMU)
PBL_ASSERT(!gpio_input_read(&ICE40LP->cdone), "CDONE not low after reset");
// Wait until CRESET goes high again. It's open-drain (and someone with
// tweezers might be grounding it) so it may take some time.
PBL_ASSERT(prv_spin_until_creset_is(true), "CRESET not high after reset");
// iCE40 Programming and Configuration manual specifies that the iCE40 needs
// 800 µs for "housekeeping" after reset is released before it is ready to
// receive its configuration.
delay_us(1000);
#endif
SLEDecodeContext sle_ctx;
sle_decode_init(&sle_ctx, fpga_bitstream);
uint8_t byte;
while (sle_decode(&sle_ctx, &byte)) {
spi_ll_slave_write(ICE40LP->spi_port, byte);
}
// Set SCS high so that we don't process any of these clocks as commands.
spi_ll_slave_scs_deassert(ICE40LP->spi_port);
static const uint8_t spi_zeros[9] = {0, 0, 0, 0, 0, 0, 0, 0, 0};
// 49+ SCLK cycles to tell FPGA we're done configuration.
spi_ll_slave_burst_write(ICE40LP->spi_port, spi_zeros, ARRAY_LENGTH(spi_zeros));
spi_ll_slave_release(ICE40LP->spi_port);
// PBL-19516
#if !defined(TARGET_QEMU)
prv_wait_programmed();
if (!gpio_input_read(&ICE40LP->cdone)) {
PBL_LOG(LOG_LEVEL_ERROR, "CDONE not high after programming");
return false;
}
#endif
return true;
}
void display_program(const uint8_t *fpga_bitstream, uint32_t bitstream_size) {
periph_config_acquire_lock();
int attempt = 1;
while (1) {
if (prv_try_program(fpga_bitstream, bitstream_size)) {
break;
}
if (attempt++ >= 3) {
PBL_CROAK("Too many failed FPGA programming attempts");
}
}
spi_slave_set_frequency(ICE40LP->spi_port, ICE40LP->fast_spi_frequency);
periph_config_release_lock();
}
bool display_switch_to_bootloader_mode(void) {
// Reset the FPGA and wait for it to program itself via NVCM.
// NVCM configuration is initiated by pulling CRESET high while SCS is high.
periph_config_acquire_lock();
// SCS will already be high here.
// CRESET needs to be low for at least 200 ns
gpio_output_set(&ICE40LP->creset, false);
delay_us(1000);
gpio_output_set(&ICE40LP->creset, true);
bool success = prv_wait_programmed();
if (success) {
display_spi_configure_default();
}
periph_config_release_lock();
return success;
}
void display_power_enable(void) {
// The display requires us to wait 1ms between each power rail coming up. The PMIC
// initialization brings up the 3.2V rail (VLCD on the display, LD02 on the PMIC) for us, but
// we still need to wait before turning on the subsequent rails.
psleep(2);
if (ICE40LP->use_6v6_rail) {
PBL_LOG(LOG_LEVEL_DEBUG, "Enabling 6v6 (Display VDDC)");
set_6V6_power_state(true);
psleep(2);
}
PBL_LOG(LOG_LEVEL_DEBUG, "Enabling 4v5 (Display VDDP)");
set_4V5_power_state(true);
}
void display_power_disable(void) {
PBL_LOG(LOG_LEVEL_DEBUG, "Disabling 4v5 (Display VDDP)");
set_4V5_power_state(false);
psleep(2);
if (ICE40LP->use_6v6_rail) {
PBL_LOG(LOG_LEVEL_DEBUG, "Disabling 6v6 (Display VDDC)");
set_6V6_power_state(false);
psleep(2);
}
}
//!
//! Starts a frame.
//!
void display_start_frame(void) {
// The iCE40UL framebuffer FPGA (S4) configuration requires a short delay
// after asserting SCS before it is ready for a command.
delay_us(5);
spi_ll_slave_write(ICE40LP->spi_port, CMD_FRAME_BEGIN);
// Make sure command has been transferred.
spi_slave_wait_until_idle_blocking(ICE40LP->spi_port);
}

View file

@ -0,0 +1,45 @@
/*
* 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.
*/
#pragma once
#include "drivers/gpio.h"
#include <stdbool.h>
typedef enum {
CMD_FRAME_BEGIN = 0x5,
} DisplayCmd;
void display_spi_begin_transaction(void);
void display_spi_end_transaction(void);
void display_spi_configure_default(void);
bool display_busy(void);
void display_start(void);
void display_program(const uint8_t *fpga_bitstream, uint32_t bitstream_size);
void display_send_clocks(uint32_t count);
void display_start_frame(void);
void display_write_byte(uint8_t d);
void display_send_cmd(DisplayCmd cmd);
void display_power_enable(void);
void display_power_disable(void);
//! Reset the FPGA into bootloader mode.
//!
//! @return true if successful, false if the NVCM is not programmed.
bool display_switch_to_bootloader_mode(void);

View file

@ -0,0 +1,136 @@
/*
* 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/display/ice40lp/snowy_boot.h"
#include "drivers/display/ice40lp/ice40lp_definitions.h"
#include "drivers/display/ice40lp/ice40lp_internal.h"
#include "board/board.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/pmic.h"
#include "drivers/spi.h"
#include "system/logging.h"
#include "system/passert.h"
#include "kernel/util/delay.h"
#include <stdbool.h>
#include <stdint.h>
#define CMD_NULL (0)
#define CMD_SET_PARAMETER (1)
#define CMD_DISPLAY_OFF (2)
#define CMD_DISPLAY_ON (3)
#define CMD_DRAW_SCENE (4)
#define SCENE_BLACK (0)
#define SCENE_SPLASH (1)
#define SCENE_UPDATE (2)
#define SCENE_ERROR (3)
#define UPDATE_PROGRESS_MAX (93)
static void prv_start_command(uint8_t cmd) {
display_spi_begin_transaction();
spi_ll_slave_write(ICE40LP->spi_port, cmd);
}
static void prv_send_command_arg(uint8_t arg) {
spi_ll_slave_write(ICE40LP->spi_port, arg);
}
static void prv_end_command(void) {
display_spi_end_transaction();
}
static bool prv_wait_busy(void) {
// The display should come out of busy within 35 milliseconds;
// it is a waste of time to wait more than twice that.
int timeout = 50 * 10;
while (display_busy()) {
if (timeout-- == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "Display busy-wait timeout expired!");
return false;
}
delay_us(100);
}
return true;
}
static void prv_screen_on(void) {
prv_start_command(CMD_DISPLAY_ON);
prv_end_command();
}
static void prv_screen_off(void) {
prv_start_command(CMD_DISPLAY_OFF);
prv_end_command();
}
void prv_draw_scene(uint8_t scene) {
prv_start_command(CMD_DRAW_SCENE);
prv_send_command_arg(scene);
prv_end_command();
}
void prv_set_parameter(uint32_t param) {
prv_start_command(CMD_SET_PARAMETER);
// Send in little-endian byte order
prv_send_command_arg(param & 0xff);
prv_send_command_arg((param >> 8) & 0xff);
prv_send_command_arg((param >> 16) & 0xff);
prv_send_command_arg((param >> 24) & 0xff);
prv_end_command();
}
void boot_display_show_boot_splash(void) {
prv_wait_busy();
prv_draw_scene(SCENE_SPLASH);
// Don't turn the screen on until the boot-splash is fully drawn.
prv_wait_busy();
prv_screen_on();
}
void boot_display_show_firmware_update_progress(
uint32_t numerator, uint32_t denominator) {
static uint8_t last_bar_fill = UINT8_MAX;
// Scale progress to the number of pixels in the progress bar,
// rounding half upwards.
uint8_t bar_fill =
((numerator * UPDATE_PROGRESS_MAX) + ((denominator+1)/2)) / denominator;
// Don't waste time and power redrawing the same screen repeatedly.
if (bar_fill != last_bar_fill) {
last_bar_fill = bar_fill;
prv_set_parameter(bar_fill);
prv_draw_scene(SCENE_UPDATE);
}
}
bool boot_display_show_error_code(uint32_t error_code) {
prv_set_parameter(error_code);
prv_draw_scene(SCENE_ERROR);
if (prv_wait_busy()) {
prv_screen_on();
return true;
} else {
return false;
}
}
void boot_display_screen_off(void) {
prv_screen_off();
prv_draw_scene(SCENE_BLACK);
prv_wait_busy();
}

View file

@ -0,0 +1,38 @@
/*
* 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 <stdint.h>
//! Functions for controlling the display FPGA in bootloader mode, such as
//! early in the boot process before it is reconfigured in framebuffer mode.
//!
//! These functions all assume that all necessary GPIOs and the SPI peripheral
//! are configured correctly, and that the bootloader is already in bootloader
//! mode.
//! Display the Pebble logo and turn on the screen.
void boot_display_show_boot_splash(void);
//! Show the Pebble logo with a progress bar.
void boot_display_show_firmware_update_progress(
uint32_t numerator, uint32_t denominator);
//! Show a sad-watch error.
bool boot_display_show_error_code(uint32_t error_code);
//! Black out the screen and prepare for power down.
void boot_display_screen_off(void);

View file

@ -0,0 +1,396 @@
/*
* 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 "sharp_ls013b7dh01.h"
#include "applib/graphics/gtypes.h"
#include "board/board.h"
#include "debug/power_tracking.h"
#include "drivers/dma.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/spi.h"
#include "kernel/util/sleep.h"
#include "kernel/util/stop.h"
#include "os/tick.h"
#include "services/common/analytics/analytics.h"
#include "system/logging.h"
#include "system/passert.h"
#include "util/bitset.h"
#include "util/net.h"
#include "util/reverse.h"
#include "util/units.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#include <mcu.h>
#include "misc.h"
#include "FreeRTOS.h"
#include "task.h"
#include "semphr.h"
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
// GPIO constants
static const unsigned int DISP_MODE_STATIC = 0x00;
static const unsigned int DISP_MODE_WRITE = 0x80;
static const unsigned int DISP_MODE_CLEAR = 0x20;
// We want the SPI clock to run at 2MHz by default
static uint32_t s_spi_clock_hz;
// DMA constants
static DMA_Stream_TypeDef* DISPLAY_DMA_STREAM = DMA1_Stream4;
static const uint32_t DISPLAY_DMA_CLOCK = RCC_AHB1Periph_DMA1;
static bool s_initialized = false;
// DMA state
static DisplayContext s_display_context;
static uint32_t s_dma_line_buffer[DISP_DMA_BUFFER_SIZE_WORDS];
static SemaphoreHandle_t s_dma_update_in_progress_semaphore;
static void prv_display_write_byte(uint8_t d);
static void prv_display_context_init(DisplayContext* context);
static void prv_setup_dma_transfer(uint8_t* framebuffer_addr, int framebuffer_size);
static bool prv_do_dma_update(void);
static void prv_enable_display_spi_clock() {
periph_config_enable(BOARD_CONFIG_DISPLAY.spi, BOARD_CONFIG_DISPLAY.spi_clk);
power_tracking_start(PowerSystemMcuSpi2);
}
static void prv_disable_display_spi_clock() {
periph_config_disable(BOARD_CONFIG_DISPLAY.spi, BOARD_CONFIG_DISPLAY.spi_clk);
power_tracking_stop(PowerSystemMcuSpi2);
}
static void prv_enable_chip_select(void) {
gpio_output_set(&BOARD_CONFIG_DISPLAY.cs, true);
// setup time > 3us
// this produces a setup time of ~7us
for (volatile int i = 0; i < 32; i++);
}
static void prv_disable_chip_select(void) {
// delay while last byte is emitted by the SPI peripheral (~7us)
for (volatile int i = 0; i < 48; i++);
gpio_output_set(&BOARD_CONFIG_DISPLAY.cs, false);
// hold time > 1us
// this produces a delay of ~3.5us
for (volatile int i = 0; i < 16; i++);
}
static void prv_display_start(void) {
periph_config_acquire_lock();
gpio_af_init(&BOARD_CONFIG_DISPLAY.clk, GPIO_OType_PP, GPIO_Speed_50MHz, GPIO_PuPd_NOPULL);
gpio_af_init(&BOARD_CONFIG_DISPLAY.mosi, GPIO_OType_PP, GPIO_Speed_50MHz, GPIO_PuPd_NOPULL);
gpio_output_init(&BOARD_CONFIG_DISPLAY.cs, GPIO_OType_PP, GPIO_Speed_50MHz);
gpio_output_init(&BOARD_CONFIG_DISPLAY.on_ctrl,
BOARD_CONFIG_DISPLAY.on_ctrl_otype,
GPIO_Speed_50MHz);
if (BOARD_CONFIG.power_5v0_options != OptionNotPresent) {
GPIOOType_TypeDef otype = (BOARD_CONFIG.power_5v0_options == OptionActiveLowOpenDrain)
? GPIO_OType_OD : GPIO_OType_PP;
gpio_output_init(&BOARD_CONFIG.power_ctl_5v0, otype, GPIO_Speed_50MHz);
}
if (BOARD_CONFIG.lcd_com.gpio) {
gpio_output_init(&BOARD_CONFIG.lcd_com, GPIO_OType_PP, GPIO_Speed_50MHz);
}
// Set up a SPI bus on SPI2
SPI_InitTypeDef spi_cfg;
SPI_I2S_DeInit(BOARD_CONFIG_DISPLAY.spi);
SPI_StructInit(&spi_cfg);
spi_cfg.SPI_Direction = SPI_Direction_1Line_Tx; // Write-only SPI
spi_cfg.SPI_Mode = SPI_Mode_Master;
spi_cfg.SPI_DataSize = SPI_DataSize_8b;
spi_cfg.SPI_CPOL = SPI_CPOL_Low;
spi_cfg.SPI_CPHA = SPI_CPHA_1Edge;
spi_cfg.SPI_NSS = SPI_NSS_Soft;
spi_cfg.SPI_BaudRatePrescaler =
spi_find_prescaler(s_spi_clock_hz, BOARD_CONFIG_DISPLAY.spi_clk_periph);
spi_cfg.SPI_FirstBit = SPI_FirstBit_MSB;
SPI_Init(BOARD_CONFIG_DISPLAY.spi, &spi_cfg);
gpio_use(BOARD_CONFIG_DISPLAY.spi_gpio);
SPI_Cmd(BOARD_CONFIG_DISPLAY.spi, ENABLE);
gpio_release(BOARD_CONFIG_DISPLAY.spi_gpio);
if (BOARD_CONFIG.power_5v0_options != OptionNotPresent) {
// +5V to 5V_EN pin
gpio_output_set(&BOARD_CONFIG.power_ctl_5v0, true);
}
// +5V to LCD_DISP pin (Set this pin low to turn off the display)
gpio_output_set(&BOARD_CONFIG_DISPLAY.on_ctrl, true);
periph_config_release_lock();
}
uint32_t display_baud_rate_change(uint32_t new_frequency_hz) {
// Take the semaphore so that we can be sure that we are not interrupting a transfer
xSemaphoreTake(s_dma_update_in_progress_semaphore, portMAX_DELAY);
uint32_t old_spi_clock_hz = s_spi_clock_hz;
s_spi_clock_hz = new_frequency_hz;
prv_enable_display_spi_clock();
prv_display_start();
prv_disable_display_spi_clock();
xSemaphoreGive(s_dma_update_in_progress_semaphore);
return old_spi_clock_hz;
}
void display_init(void) {
if (s_initialized) {
return;
}
s_spi_clock_hz = MHZ_TO_HZ(2);
prv_display_context_init(&s_display_context);
vSemaphoreCreateBinary(s_dma_update_in_progress_semaphore);
dma_request_init(SHARP_SPI_TX_DMA);
prv_enable_display_spi_clock();
prv_display_start();
prv_disable_display_spi_clock();
s_initialized = true;
}
static void prv_display_context_init(DisplayContext* context) {
context->state = DISPLAY_STATE_IDLE;
context->get_next_row = NULL;
context->complete = NULL;
}
// Clear-all mode is entered by sending 0x04 to the panel
void display_clear(void) {
prv_enable_display_spi_clock();
prv_enable_chip_select();
prv_display_write_byte(DISP_MODE_CLEAR);
prv_display_write_byte(0x00);
prv_disable_chip_select();
prv_disable_display_spi_clock();
}
bool display_update_in_progress(void) {
if (xSemaphoreTake(s_dma_update_in_progress_semaphore, 0) == pdPASS) {
xSemaphoreGive(s_dma_update_in_progress_semaphore);
return false;
}
return true;
}
void display_update(NextRowCallback nrcb, UpdateCompleteCallback uccb) {
PBL_ASSERTN(nrcb != NULL);
PBL_ASSERTN(uccb != NULL);
stop_mode_disable(InhibitorDisplay);
xSemaphoreTake(s_dma_update_in_progress_semaphore, portMAX_DELAY);
analytics_stopwatch_start(ANALYTICS_APP_METRIC_DISPLAY_WRITE_TIME, AnalyticsClient_App);
analytics_inc(ANALYTICS_DEVICE_METRIC_DISPLAY_UPDATES_PER_HOUR, AnalyticsClient_System);
prv_enable_display_spi_clock();
power_tracking_start(PowerSystemMcuDma1);
SPI_I2S_DMACmd(BOARD_CONFIG_DISPLAY.spi, SPI_I2S_DMAReq_Tx, ENABLE);
prv_display_context_init(&s_display_context);
s_display_context.get_next_row = nrcb;
s_display_context.complete = uccb;
prv_do_dma_update();
// Block while we wait for the update to finish.
TickType_t ticks = milliseconds_to_ticks(4000); // DMA should be fast
if (xSemaphoreTake(s_dma_update_in_progress_semaphore, ticks) != pdTRUE) {
// something went wrong, gather some debug info & reset
int dma_status = DMA_GetITStatus(DISPLAY_DMA_STREAM, DMA_IT_TCIF4);
uint32_t spi_clock_status = (RCC->APB1ENR & BOARD_CONFIG_DISPLAY.spi_clk);
uint32_t dma_clock_status = (RCC->AHB1ENR & DISPLAY_DMA_CLOCK);
uint32_t pri_mask = __get_PRIMASK();
PBL_CROAK("display DMA failed: 0x%" PRIx32 " %d 0x%lx 0x%lx", pri_mask,
dma_status, spi_clock_status, dma_clock_status);
}
power_tracking_stop(PowerSystemMcuDma1);
prv_disable_display_spi_clock();
xSemaphoreGive(s_dma_update_in_progress_semaphore);
stop_mode_enable(InhibitorDisplay);
analytics_stopwatch_stop(ANALYTICS_APP_METRIC_DISPLAY_WRITE_TIME);
}
// Static mode is entered by sending 0x00 to the panel
static void prv_display_enter_static(void) {
prv_enable_chip_select();
prv_display_write_byte(DISP_MODE_STATIC);
prv_display_write_byte(0x00);
prv_display_write_byte(0x00);
prv_disable_chip_select();
}
void display_pulse_vcom(void) {
PBL_ASSERTN(BOARD_CONFIG.lcd_com.gpio != 0);
gpio_output_set(&BOARD_CONFIG.lcd_com, true);
// the spec requires at least 1us; this provides ~2 so should be safe
for (volatile int i = 0; i < 8; i++);
gpio_output_set(&BOARD_CONFIG.lcd_com, false);
}
static bool prv_dma_handler(DMARequest *request, void *context) {
return prv_do_dma_update();
}
#if DISPLAY_ORIENTATION_ROTATED_180
//!
//! memcpy the src buffer to dst and reverse the bits
//! to match the display order
//!
static void prv_memcpy_reverse_bytes(uint8_t* dst, uint8_t* src, int bytes) {
// Skip the mode selection and column address bytes
dst+=2;
while (bytes--) {
*dst++ = reverse_byte(*src++);
}
}
#else
//!
//! memcpy the src buffer to dst backwards (i.e. the highest src byte
//! is the lowest byte in dst.
//!
static void prv_memcpy_backwards(uint32_t* dst, uint32_t* src, int length) {
dst += length - 1;
while (length--) {
*dst-- = ntohl(*src++);
}
}
#endif
//!
//! Write a single byte synchronously to the display. Use this
//! sparingly, as it will tie up the micro duing the write.
//!
static void prv_display_write_byte(uint8_t d) {
// Block until the tx buffer is empty
SPI_I2S_SendData(BOARD_CONFIG_DISPLAY.spi, d);
while (!SPI_I2S_GetFlagStatus(BOARD_CONFIG_DISPLAY.spi, SPI_I2S_FLAG_TXE)) {}
}
static bool prv_do_dma_update(void) {
DisplayRow r;
PBL_ASSERTN(s_display_context.get_next_row != NULL);
bool is_end_of_buffer = !s_display_context.get_next_row(&r);
switch (s_display_context.state) {
case DISPLAY_STATE_IDLE:
{
if (is_end_of_buffer) {
// If nothing has been modified, bail out early
return false;
}
// Enable display slave select
prv_enable_chip_select();
s_display_context.state = DISPLAY_STATE_WRITING;
#if DISPLAY_ORIENTATION_ROTATED_180
prv_memcpy_reverse_bytes((uint8_t*)s_dma_line_buffer, r.data, DISP_LINE_BYTES);
s_dma_line_buffer[0] &= ~(0xffff);
s_dma_line_buffer[0] |= (DISP_MODE_WRITE | reverse_byte(r.address + 1) << 8);
#else
prv_memcpy_backwards(s_dma_line_buffer, (uint32_t*)r.data, DISP_LINE_WORDS);
s_dma_line_buffer[0] &= ~(0xffff);
s_dma_line_buffer[0] |= (DISP_MODE_WRITE | reverse_byte(167 - r.address + 1) << 8);
#endif
prv_setup_dma_transfer(((uint8_t*) s_dma_line_buffer), DISP_DMA_BUFFER_SIZE_BYTES);
break;
}
case DISPLAY_STATE_WRITING:
{
if (is_end_of_buffer) {
prv_display_write_byte(0x00);
// Disable display slave select
prv_disable_chip_select();
prv_display_enter_static();
s_display_context.complete();
signed portBASE_TYPE was_higher_priority_task_woken = pdFALSE;
xSemaphoreGiveFromISR(s_dma_update_in_progress_semaphore, &was_higher_priority_task_woken);
return was_higher_priority_task_woken != pdFALSE;
}
#if DISPLAY_ORIENTATION_ROTATED_180
prv_memcpy_reverse_bytes((uint8_t*)s_dma_line_buffer, r.data, DISP_LINE_BYTES);
s_dma_line_buffer[0] &= ~(0xffff);
s_dma_line_buffer[0] |= (DISP_MODE_WRITE | reverse_byte(r.address + 1) << 8);
#else
prv_memcpy_backwards(s_dma_line_buffer, (uint32_t*)r.data, DISP_LINE_WORDS);
s_dma_line_buffer[0] &= ~(0xffff);
s_dma_line_buffer[0] |= reverse_byte(167 - r.address + 1) << 8;
#endif
prv_setup_dma_transfer(((uint8_t*) s_dma_line_buffer) + 1, DISP_DMA_BUFFER_SIZE_BYTES - 1);
break;
}
default:
WTF;
}
return false;
}
static void prv_setup_dma_transfer(uint8_t *framebuffer_addr, int framebuffer_size) {
void *dst = (void *)&(BOARD_CONFIG_DISPLAY.spi->DR);
dma_request_start_direct(SHARP_SPI_TX_DMA, dst, framebuffer_addr, framebuffer_size,
prv_dma_handler, NULL);
}
void display_show_splash_screen(void) {
// The bootloader has already drawn the splash screen for us; nothing to do!
}
// Stubs for display offset
void display_set_offset(GPoint offset) {}
GPoint display_get_offset(void) { return GPointZero; }

View file

@ -0,0 +1,38 @@
/*
* 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.
*/
#pragma once
#include "../display.h"
#define DISP_LINE_BYTES (DISP_COLS / 8)
#define DISP_LINE_WORDS (((DISP_COLS - 1) / 32) + 1)
// Bytes_per_line + 1 byte for the line address + 1 byte for a null trailer + 1 optional byte for a write command
#define DISP_DMA_BUFFER_SIZE_BYTES (DISP_LINE_BYTES + 3)
#define DISP_DMA_BUFFER_SIZE_WORDS (DISP_LINE_WORDS + 1)
typedef enum {
DISPLAY_STATE_IDLE,
DISPLAY_STATE_WRITING
} DisplayState;
typedef struct {
DisplayState state;
NextRowCallback get_next_row;
UpdateCompleteCallback complete;
} DisplayContext;

64
src/fw/drivers/dma.h Normal file
View file

@ -0,0 +1,64 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
typedef const struct DMARequest DMARequest;
//! The type of function that's called from an ISR to notify the consumer that a direct DMA transfer
//! has completed.
typedef bool (*DMADirectRequestHandler)(DMARequest *this, void *context);
//! The type of function that's called from an ISR to notify the consumer that a circular DMA
//! transfer is either complete or half transferred (specified via the `is_complete` parameter).
typedef bool (*DMACircularRequestHandler)(DMARequest *this, void *context, bool is_complete);
//! Initializes a DMA transfer and its underlying stream / controller as necessary. This is called
//! from the consumer's init function (i.e. uart_init() or compositor_dma_init()).
void dma_request_init(DMARequest *this);
//! Starts a direct DMA transfer which automatically stops and calls a callback (from an ISR) once
//! it's complete. The length should be specified in bytes.
void dma_request_start_direct(DMARequest *this, void *dst, const void *src, uint32_t length,
DMADirectRequestHandler handler, void *context);
//! Starts a circular DMA transfer which calls the callback for when the transfer is both complete
//! and half complete. The length should be specified in bytes.
//! @note The destination address must not be in a cachable region of memory (i.e. SRAM on the F7).
//! See the comment within dma.c for more info.
void dma_request_start_circular(DMARequest *this, void *dst, const void *src, uint32_t length,
DMACircularRequestHandler handler, void *context);
//! Stops an in-progress DMA transfer (typically only used for circular transfers, otherwise the
//! transfer will be stopped when it completes)
void dma_request_stop(DMARequest *this);
//! Returns whether or not the transfer is currently in progress
bool dma_request_in_progress(DMARequest *this);
//! Gets the current value of the underlying DMA stream's data counter
uint32_t dma_request_get_current_data_counter(DMARequest *this);
//! Get the current value of the transfer error flag and clears it
bool dma_request_get_and_clear_transfer_error(DMARequest *this);
//! Allows for disabling of auto-incrementing of memory buffer addresses. This is currently only
//! used by SPI in order to allow receiving of data by sending the same dummy value over and over.
void dma_request_set_memory_increment_disabled(DMARequest *this, bool disabled);

56
src/fw/drivers/exti.h Normal file
View file

@ -0,0 +1,56 @@
/*
* 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.
*/
#pragma once
#include "board/board.h"
//! For simplicity we just configure all our EXTI-related interrupts to the same priority. This
//! way we don't have to worry about different lines wanting differing priorities when they share
//! the same NVIC channel (and therefore the same priority)
#define EXTI_PRIORITY (0x0e)
typedef enum {
ExtiTrigger_Rising,
ExtiTrigger_Falling,
ExtiTrigger_RisingFalling
} ExtiTrigger;
//! See section 12.2.5 "External interrupt/event line mapping" in the STM32F2 reference manual
typedef enum {
ExtiLineOther_RTCAlarm = 17,
ExtiLineOther_RTCWakeup = 22
} ExtiLineOther;
typedef void (*ExtiHandlerCallback)(bool *should_context_switch);
//! Configures the given EXTI and NVIC for the given configuration.
void exti_configure_pin(ExtiConfig cfg, ExtiTrigger trigger, ExtiHandlerCallback cb);
//! Configures the given EXTI and NVIC for the given configuration.
void exti_configure_other(ExtiLineOther exti_line, ExtiTrigger trigger);
static inline void exti_enable(ExtiConfig config);
static inline void exti_disable(ExtiConfig config);
void exti_enable_other(ExtiLineOther exti_line);
void exti_disable_other(ExtiLineOther exti_line);
void exti_set_pending(ExtiConfig cfg);
void exti_clear_pending_other(ExtiLineOther exti_line);
#include "exti.inl.h"

28
src/fw/drivers/exti.inl.h Normal file
View file

@ -0,0 +1,28 @@
/*
* 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.
*/
//! @file exti.inl.h
//!
//! Helper functions intended to be inlined into the calling code.
static inline void exti_enable(ExtiConfig config) {
exti_enable_other(config.exti_line);
}
static inline void exti_disable(ExtiConfig config) {
exti_disable_other(config.exti_line);
}

210
src/fw/drivers/flash.h Normal file
View file

@ -0,0 +1,210 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "system/status_codes.h"
static const uint32_t EXPECTED_SPI_FLASH_ID_32MBIT = 0x20bb16;
static const uint32_t EXPECTED_SPI_FLASH_ID_64MBIT = 0x20bb17;
/**
* Configure the micro's peripherals to communicate with the flash
* chip.
*/
void flash_init(void);
//! Stop all flash transactions.
void flash_stop(void);
/**
* Retreieve the first 3 bytes of the flash's device id. This ID
* should remain fixed across all chips.
*/
uint32_t flash_whoami(void);
/**
* Read 1 or more bytes starting at the specified 24bit address into
* the provided buffer. This function does no range checking, so it is
* currently possible to run off the end of the flash.
*
* @param buffer A byte-buffer that will be used to store the data
* read from flash.
* @param start_addr The address of the first byte to be read from flash.
* @param buffer_size The total number of bytes to be read from flash.
*/
void flash_read_bytes(uint8_t* buffer, uint32_t start_addr, uint32_t buffer_size);
/**
* Write 1 or more bytes from the buffer to flash starting at the
* specified 24bit address. This function will handle both writing a
* buffer that is larger than the flash's page size and writing to a
* non-page aligned address.
*
* @param buffer A byte-buffer containing the data to be written to flash.
* @param start_addr The address of the first byte to be written to flash.
* @param buffer_size The total number of bytes to be written.
*/
void flash_write_bytes(const uint8_t* buffer, uint32_t start_addr, uint32_t buffer_size);
typedef void (*FlashOperationCompleteCb)(void *context, status_t result);
/**
* Erase a subsector asynchronously.
*
* The callback function will be called when the erase completes, whether the
* erase succeeded or failed. The callback will be executed on an arbitrary
* (possibly high-priority) task, so the callback function must return quickly.
* The callback may also be called directly from within flash_erase_subsector.
*/
void flash_erase_subsector(uint32_t subsector_addr,
FlashOperationCompleteCb on_complete,
void *context);
/**
* Erase a sector asynchronously.
*
* The callback function will be called when the erase completes, whether the
* erase succeeded or failed. The callback will be executed on an arbitrary
* (possibly high-priority) task, so the callback function must return quickly.
* The callback may also be called directly from within flash_erase_sector.
*/
void flash_erase_sector(uint32_t sector_addr,
FlashOperationCompleteCb on_complete,
void *context);
/**
* Erase the subsector containing the specified address.
*/
void flash_erase_subsector_blocking(uint32_t subsector_addr);
/**
* Erase the sector containing the specified address.
*
* Beware: this function takes 100ms+ to execute, so be careful when you call it.
*/
void flash_erase_sector_blocking(uint32_t sector_addr);
/**
* Check whether the sector containing the specified address is already erased.
*/
bool flash_sector_is_erased(uint32_t sector_addr);
/**
* Check whether the subsector containing the specified address is already erased.
*/
bool flash_subsector_is_erased(uint32_t sector_addr);
/**
* Erase the entire contents of flash.
*
* Note: This is a very slow (up to a minute) blocking operation. Don't let the watchdog kill
* you when calling this.
*/
void flash_erase_bulk(void);
/**
* Erase a region of flash asynchronously using as few erase operations as
* possible.
*
* At least (max_start, min_end) but no more than (min_start, max_end) will be
* erased. Both min_start and max_end must be aligned to a subsector address as
* that is the smallest unit that can be erased.
*/
void flash_erase_optimal_range(
uint32_t min_start, uint32_t max_start, uint32_t min_end, uint32_t max_end,
FlashOperationCompleteCb on_complete, void *context);
/**
* Configure the flash driver to enter a deep sleep mode between commands.
*/
void flash_sleep_when_idle(bool enable);
//! @return True if sleeping when idle is currently enabled.
bool flash_get_sleep_when_idle(void);
void debug_flash_dump_registers(void);
//! @return true if the flash peripheral has been initialized.
bool flash_is_initialized(void);
//! Helper function to check that the Flash ID (whoami) is correct
//! @return true if the flash ID matches what we expect based on the board config
bool flash_is_whoami_correct(void);
//! Helper function to extract the Flash Size from the ID (whoami)
//! @return the size of the flash in bytes
size_t flash_get_size(void);
// This is only intended to be called when entering stop mode. It does not use
// any locks because IRQs have already been disabled. The idea is to only incur
// the wait penalty for entering/exiting deep sleep mode for the flash
// before/after stop mode. The flash part consumes ~100uA in standby mode and
// ~10uA when its in deep sleep mode. If the MCU is not in stop mode, this
// difference is negligible
void flash_power_down_for_stop_mode(void);
void flash_power_up_after_stop_mode(void);
typedef enum {
FLASH_MODE_ASYNC = 0,
FLASH_MODE_SYNC_BURST,
// Add new modes above this
FLASH_MODE_NUM_MODES
}FlashModeType;
/**
* Manually switches modes between asynchronous/synchronous
*
*/
void flash_switch_mode(FlashModeType mode);
// Returns the sector address that the given flash address lies in
uint32_t flash_get_sector_base_address(uint32_t flash_addr);
// Returns the subsector address that the given flash address lies in
uint32_t flash_get_subsector_base_address(uint32_t flash_addr);
// Enable write protection on flash
void flash_enable_write_protection(void);
// Write-protects the prf region of flash
void flash_prf_set_protection(bool do_protect);
//! Compute a CRC32 checksum of a region of flash.
uint32_t flash_crc32(uint32_t flash_addr, uint32_t length);
//! Apply the legacy defective checksum to a region of flash.
uint32_t flash_calculate_legacy_defective_checksum(uint32_t flash_addr,
uint32_t length);
//! Call this before any external flash access (including memory-mapped)
//! to power on the flash peripheral if it wasn't already, and
//! to increase the internal reference counter that prevents flash peripheral from powering down.
void flash_use(void);
//! Convenience for \ref flash_release_many(1)
void flash_release(void);
//! Call this after you finished accessing external flash
//! to decrease the internal reference counter by num_locks, and
//! to turn off the flash peripheral if the reference counter reaches 0
//! param num_locks usually 1, the amount by which the reference counter should be decremented
void flash_release_many(uint32_t num_locks);

View file

@ -0,0 +1,16 @@
Flash Memory Drivers
--------------------
Flash memory access is exposed through two separate APIs. The main API, defined
in `flash.h` and implemented in `flash_api.c`, is used almost everywhere. There
is also an alternate API used exclusively for performing core dumps, implemented
in `cd_flash_driver.c`. The alternate API is carefully implemented to be usable
regardless of how messed up the system state is in by not relying on any OS
services.
The flash APIs are written to be agnostic to the specific type of flash used.
They are written against the generic low-level driver interface defined in
`flash_impl.h`. Each low-level driver is specific to a combination of
flash memory part and microcontroller interface. The low-level drivers make no
use of OS services so that they can be used for both the main and core dump
driver APIs.

View file

@ -0,0 +1,100 @@
/*
* 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 <inttypes.h>
#include "drivers/flash.h"
#include "drivers/flash/flash_impl.h"
#include "drivers/watchdog.h"
#include "flash_region/flash_region.h"
#include "kernel/util/delay.h"
#include "kernel/core_dump_private.h"
//! We have our own flash driver for coredump support because it must not use
//! any FreeRTOS constructs & we want to keep it as simple as possible. In
//! addition we want the flexibility to be able to reset the flash driver to
//! get it into a working state
void cd_flash_init(void) {
// Reset & (re)initialize the flash HW
flash_impl_init(true /* coredump_mode */);
// Protect the PRF region from writes
flash_impl_write_protect(
FLASH_REGION_SAFE_FIRMWARE_BEGIN,
(FLASH_REGION_SAFE_FIRMWARE_END - SECTOR_SIZE_BYTES));
}
void cd_flash_erase_region(uint32_t start_addr, uint32_t total_bytes) {
CD_ASSERTN(((start_addr & SUBSECTOR_ADDR_MASK) == start_addr) &&
((total_bytes & SUBSECTOR_ADDR_MASK) == total_bytes));
while (total_bytes > 0) {
watchdog_feed();
uint32_t erase_size = 0;
if (((start_addr & SECTOR_ADDR_MASK) == start_addr) &&
(total_bytes >= SECTOR_SIZE_BYTES)) {
erase_size = SECTOR_SIZE_BYTES;
flash_impl_erase_sector_begin(start_addr);
} else if ((start_addr & SUBSECTOR_ADDR_MASK) == start_addr &&
(total_bytes >= SUBSECTOR_SIZE_BYTES)) {
erase_size = SUBSECTOR_SIZE_BYTES;
flash_impl_erase_subsector_begin(start_addr);
} else {
// Unaligned start address or unaligned erase size
CD_ASSERTN(0);
}
status_t status;
while ((status = flash_impl_get_erase_status()) == E_BUSY) delay_us(100);
CD_ASSERTN(status == S_SUCCESS);
total_bytes -= erase_size;
start_addr += erase_size;
}
watchdog_feed();
}
uint32_t cd_flash_write_bytes(const void *buffer_ptr, uint32_t start_addr,
const uint32_t buffer_size) {
CD_ASSERTN(((start_addr + buffer_size) <= CORE_DUMP_FLASH_END) &&
(int)start_addr >= CORE_DUMP_FLASH_START);
const uint8_t *buffer = buffer_ptr;
uint32_t remaining = buffer_size;
while (remaining) {
int written = flash_impl_write_page_begin(buffer, start_addr, remaining);
CD_ASSERTN(PASSED(written));
status_t status;
while ((status = flash_impl_get_write_status()) == E_BUSY) {
delay_us(10);
}
CD_ASSERTN(PASSED(status));
buffer += written;
start_addr += written;
remaining -= written;
}
return buffer_size;
}
void cd_flash_read_bytes(void* buffer_ptr, uint32_t start_addr,
uint32_t buffer_size) {
flash_impl_read_sync(buffer_ptr, start_addr, buffer_size);
}

View file

@ -0,0 +1,599 @@
/*
* 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/flash.h"
#include "drivers/flash/flash_internal.h"
#include <inttypes.h>
#include <stdbool.h>
#include <stdint.h>
#include "drivers/flash/flash_impl.h"
#include "drivers/task_watchdog.h"
#include "drivers/watchdog.h"
#include "flash_region/flash_region.h"
#include "kernel/util/stop.h"
#include "os/mutex.h"
#include "os/tick.h"
#include "process_management/worker_manager.h"
#include "services/common/analytics/analytics.h"
#include "services/common/new_timer/new_timer.h"
#include "system/logging.h"
#include "system/passert.h"
#include "kernel/util/sleep.h"
#include "FreeRTOS.h"
#include "semphr.h"
#define MAX_ERASE_RETRIES (3)
static PebbleMutex *s_flash_lock;
static SemaphoreHandle_t s_erase_semphr;
static struct FlashEraseContext {
bool in_progress;
bool suspended;
bool is_subsector;
uint8_t retries;
PebbleTask task;
uint32_t address;
FlashOperationCompleteCb on_complete_cb;
void *cb_context;
uint32_t expected_duration;
} s_erase = { 0 };
static TimerID s_erase_poll_timer;
static TimerID s_erase_suspend_timer;
static uint32_t s_analytics_read_count;
static uint32_t s_analytics_read_bytes_count;
static uint32_t s_analytics_write_bytes_count;
static uint32_t s_system_analytics_read_bytes_count = 0;
static uint32_t s_system_analytics_write_bytes_count = 0;
static uint8_t s_system_analytics_erase_count = 0;
void analytics_external_collect_system_flash_statistics(void) {
analytics_set(ANALYTICS_DEVICE_METRIC_FLASH_READ_BYTES_COUNT,
s_system_analytics_read_bytes_count, AnalyticsClient_System);
analytics_set(ANALYTICS_DEVICE_METRIC_FLASH_WRITE_BYTES_COUNT,
s_system_analytics_write_bytes_count, AnalyticsClient_System);
analytics_set(ANALYTICS_DEVICE_METRIC_FLASH_ERASE_COUNT,
s_system_analytics_erase_count, AnalyticsClient_System);
s_system_analytics_read_bytes_count = 0;
s_system_analytics_write_bytes_count = 0;
s_system_analytics_erase_count = 0;
}
void analytics_external_collect_app_flash_read_stats(void) {
analytics_set(ANALYTICS_APP_METRIC_FLASH_READ_COUNT,
s_analytics_read_count, AnalyticsClient_App);
analytics_set(ANALYTICS_APP_METRIC_FLASH_READ_BYTES_COUNT,
s_analytics_read_bytes_count, AnalyticsClient_App);
analytics_set(ANALYTICS_APP_METRIC_FLASH_WRITE_BYTES_COUNT,
s_analytics_write_bytes_count, AnalyticsClient_App);
// The overhead cost of tracking whether each flash read was due to the foreground
// or background app is large, so the best we can do is to attribute to both of them
if (worker_manager_get_current_worker_md() != NULL) {
analytics_set(ANALYTICS_APP_METRIC_FLASH_READ_COUNT,
s_analytics_read_count, AnalyticsClient_Worker);
analytics_set(ANALYTICS_APP_METRIC_FLASH_READ_BYTES_COUNT,
s_analytics_read_bytes_count, AnalyticsClient_Worker);
analytics_set(ANALYTICS_APP_METRIC_FLASH_WRITE_BYTES_COUNT,
s_analytics_write_bytes_count, AnalyticsClient_Worker);
}
s_analytics_read_count = 0;
s_analytics_read_bytes_count = 0;
s_analytics_write_bytes_count = 0;
}
//! Assumes that s_flash_lock is held.
static status_t prv_try_restart_interrupted_erase(bool is_subsector,
uint32_t addr) {
status_t status = is_subsector? flash_impl_erase_subsector_begin(addr)
: flash_impl_erase_sector_begin(addr);
if (FAILED(status)) {
PBL_LOG(LOG_LEVEL_ERROR, "Got error trying to reissue interrupted erase: "
"%"PRIi32, status);
return status;
}
// Hopefully the task watchdog isn't enabled; this could take a while.
while (1) {
psleep(10);
status = flash_impl_get_erase_status();
if (status != E_BUSY && status != E_AGAIN) {
// Success or failure
return status;
}
}
}
void flash_init(void) {
if (s_flash_lock) {
return; // Already initialized
}
s_flash_lock = mutex_create();
s_erase_semphr = xSemaphoreCreateBinary();
xSemaphoreGive(s_erase_semphr);
s_erase_poll_timer = new_timer_create();
s_erase_suspend_timer = new_timer_create();
flash_erase_init();
mutex_lock(s_flash_lock);
flash_impl_init(false /* coredump_mode */);
uint32_t erase_in_progress_address = 0;
bool is_subsector = false;
if (flash_impl_get_nvram_erase_status(
&is_subsector, &erase_in_progress_address) == S_TRUE) {
// An erase was interrupted by e.g. a crash. Retry the erase so the
// incompletely-erased sector doesn't cause us trouble later on.
PBL_LOG(LOG_LEVEL_WARNING, "Flash erase to 0x%"PRIx32" was interrupted "
"last boot. Restarting the erase...", erase_in_progress_address);
// When an erase is interrupted, subsequent erases of the same sector tend to
// take an exceptionally long time and may even outright fail. Try the erase a
// few times before giving up.
int attempt = 1;
while (true) {
status_t status = prv_try_restart_interrupted_erase(
is_subsector, erase_in_progress_address);
if (PASSED(status)) {
break;
}
PBL_LOG(LOG_LEVEL_ERROR, "Flash erase failed, status %"PRIi32, status);
if (attempt++ >= MAX_ERASE_RETRIES) {
// We've tried all we can. No point in croaking; it's not like a reboot
// is going to fix anything. Best we can do is pretend like nothing is
// wrong and hope for the best.
PBL_LOG(LOG_LEVEL_ERROR, "Giving up on restarting the flash erase.");
break;
}
}
}
flash_impl_clear_nvram_erase_status();
mutex_unlock(s_flash_lock);
}
#if UNITTEST
void flash_api_reset_for_test(void) {
s_erase = (struct FlashEraseContext) {0};
s_flash_lock = NULL;
}
TimerID flash_api_get_erase_poll_timer_for_test(void) {
return s_erase_poll_timer;
}
#endif
//! Assumes that s_flash_lock is held.
static void prv_erase_pause(void) {
if (s_erase.in_progress && !s_erase.suspended) {
// If an erase is in progress, make sure it gets at least a mininum time slice to progress.
// If not, the successive kicking of the suspend timer could starve it out completely
psleep(100);
task_watchdog_bit_set(s_erase.task);
status_t status = flash_impl_erase_suspend(s_erase.address);
PBL_ASSERT(PASSED(status), "Erase suspend failure: %" PRId32, status);
if (status == S_NO_ACTION_REQUIRED) {
// The erase has already completed. No need to resume.
s_erase.in_progress = false;
} else {
s_erase.suspended = true;
}
}
}
//! Assumes that s_flash_lock is held.
static void prv_erase_resume(void) {
if (s_erase.suspended) {
status_t status = flash_impl_erase_resume(s_erase.address);
PBL_ASSERT(PASSED(status), "Erase resume failure: %" PRId32, status);
s_erase.suspended = false;
}
}
static void prv_erase_suspend_timer_cb(void *unused) {
mutex_lock(s_flash_lock);
prv_erase_resume();
mutex_unlock(s_flash_lock);
}
void flash_read_bytes(uint8_t* buffer, uint32_t start_addr,
uint32_t buffer_size) {
mutex_lock(s_flash_lock);
s_analytics_read_count++;
s_analytics_read_bytes_count += buffer_size;
s_system_analytics_read_bytes_count += buffer_size;
// TODO: use DMA when possible
// TODO: be smarter about pausing erases. Some flash chips allow concurrent
// reads while an erase is in progress, as long as the read is to another bank
// than the one being erased.
prv_erase_pause();
new_timer_start(s_erase_suspend_timer, 5, prv_erase_suspend_timer_cb, NULL, 0);
flash_impl_read_sync(buffer, start_addr, buffer_size);
mutex_unlock(s_flash_lock);
}
#ifdef TEST_FLASH_LOCK_PROTECTION
static bool s_assert_write_error = false;
void flash_expect_program_failure(bool expect_failure) {
s_assert_write_error = expect_failure;
}
#endif
void flash_write_bytes(const uint8_t *buffer, uint32_t start_addr,
uint32_t buffer_size) {
mutex_lock(s_flash_lock);
stop_mode_disable(InhibitorFlash); // FIXME: PBL-18028
s_analytics_write_bytes_count += buffer_size;
s_system_analytics_write_bytes_count += buffer_size;
prv_erase_pause();
new_timer_start(s_erase_suspend_timer, 50, prv_erase_suspend_timer_cb, NULL, 0);
while (buffer_size) {
int written = flash_impl_write_page_begin(buffer, start_addr, buffer_size);
PBL_ASSERT(
#ifdef TEST_FLASH_LOCK_PROTECTION
s_assert_write_error ||
#endif
PASSED(written),
"flash_impl_write_page_begin failed: %d", written);
status_t status;
while ((status = flash_impl_get_write_status()) == E_BUSY) {
psleep(0);
}
#ifdef TEST_FLASH_LOCK_PROTECTION
if (s_assert_write_error) {
PBL_ASSERT(FAILED(status), "flash write unexpectedly succeeded: %" PRId32,
status);
} else {
#endif
PBL_ASSERT(PASSED(status), "flash_impl_get_write_status returned %" PRId32,
status);
#ifdef TEST_FLASH_LOCK_PROTECTION
}
#endif
buffer += written;
start_addr += written;
buffer_size -= written;
// Give higher-priority tasks a chance to access the flash in between
// each page write.
// TODO: uncomment the lines below to resolve PBL-17503
// if (buffer_size) {
// mutex_unlock(s_flash_lock);
// mutex_lock(s_flash_lock);
// }
}
stop_mode_enable(InhibitorFlash);
mutex_unlock(s_flash_lock);
}
// Returns 0 if the erase has completed, or a non-zero expected duration (in
// ms) if not. If the erase has not finished (non-zero has been returned), the
// caller is responsible for calling the prv_flash_erase_poll() method until
// the erase completes.
static uint32_t prv_flash_erase_start(uint32_t addr,
FlashOperationCompleteCb on_complete_cb,
void *context,
bool is_subsector,
uint8_t retries) {
xSemaphoreTake(s_erase_semphr, portMAX_DELAY);
mutex_lock(s_flash_lock);
PBL_ASSERTN(s_erase.in_progress == false);
s_erase = (struct FlashEraseContext) {
.in_progress = true,
.task = pebble_task_get_current(),
.retries = retries,
// FIXME: We should just assert that the address is already aligned. If
// someone is depending on this behaviour without already knowing the range
// that's being erased they're going to have a bad time. This will probably
// cause some client fallout though, so tackle this later.
.is_subsector = is_subsector,
.address = is_subsector? flash_impl_get_subsector_base_address(addr)
: flash_impl_get_sector_base_address(addr),
.on_complete_cb = on_complete_cb,
.cb_context = context,
.expected_duration = is_subsector?
flash_impl_get_typical_subsector_erase_duration_ms() :
flash_impl_get_typical_sector_erase_duration_ms(),
};
stop_mode_disable(InhibitorFlash); // FIXME: PBL-18028
status_t status = is_subsector? flash_impl_blank_check_subsector(addr)
: flash_impl_blank_check_sector(addr);
PBL_ASSERT(PASSED(status), "Blank check error: %" PRId32, status);
if (status != S_FALSE) {
stop_mode_enable(InhibitorFlash);
s_erase.in_progress = false;
mutex_unlock(s_flash_lock);
xSemaphoreGive(s_erase_semphr);
// Only run the callback with no locks held so that the callback won't
// deadlock if it kicks off another sector erase.
on_complete_cb(context, S_NO_ACTION_REQUIRED);
return 0;
}
analytics_inc(ANALYTICS_APP_METRIC_FLASH_SUBSECTOR_ERASE_COUNT,
AnalyticsClient_CurrentTask);
s_system_analytics_erase_count++;
status = is_subsector? flash_impl_erase_subsector_begin(addr)
: flash_impl_erase_sector_begin(addr);
if (PASSED(status)) {
flash_impl_set_nvram_erase_status(is_subsector, addr);
mutex_unlock(s_flash_lock);
return (s_erase.expected_duration * 7 / 8);
} else {
stop_mode_enable(InhibitorFlash);
s_erase.in_progress = false;
mutex_unlock(s_flash_lock);
xSemaphoreGive(s_erase_semphr);
// Only run the callback with no locks held so that the callback won't
// deadlock if it kicks off another sector erase.
on_complete_cb(context, status);
return 0;
}
}
// Returns non-zero expected remaining time if the erase has not finished. If the erase
// has finished it will re-enable stop-mode, clear the in_progress flag and call the
// completed callback before returning 0.
static uint32_t prv_flash_erase_poll(void) {
mutex_lock(s_flash_lock);
status_t status = flash_impl_get_erase_status();
bool erase_finished;
struct FlashEraseContext saved_ctx = s_erase;
switch (status) {
case E_BUSY:
case E_AGAIN:
erase_finished = false;
break;
case S_SUCCESS:
default:
// Success or failure; the erase has finished either way.
erase_finished = true;
break;
}
if (erase_finished) {
stop_mode_enable(InhibitorFlash);
s_erase.in_progress = false;
flash_impl_clear_nvram_erase_status();
}
mutex_unlock(s_flash_lock);
if (!erase_finished) {
return s_erase.expected_duration / 8;
}
xSemaphoreGive(s_erase_semphr);
if (status == E_ERROR && saved_ctx.retries < MAX_ERASE_RETRIES) {
// Try issuing the erase again. It might succeed this time around.
PBL_LOG(LOG_LEVEL_DEBUG, "Erase of 0x%"PRIx32" failed (attempt %d)."
" Trying again...", saved_ctx.address, saved_ctx.retries);
return prv_flash_erase_start(
saved_ctx.address, saved_ctx.on_complete_cb, saved_ctx.cb_context,
saved_ctx.is_subsector, saved_ctx.retries + 1);
} else {
// Only run the callback with no locks held so that the callback won't
// deadlock if it kicks off another sector erase.
saved_ctx.on_complete_cb(saved_ctx.cb_context, status);
return 0;
}
}
// Timer callback that checks to see if the erase has finished. Used by the non-blocking
// routines.
static void prv_flash_erase_timer_cb(void *context) {
uint32_t remaining_ms = prv_flash_erase_poll();
if (remaining_ms) {
// Erase is in progress or suspended; poll again later.
new_timer_start(s_erase_poll_timer, remaining_ms, prv_flash_erase_timer_cb, NULL, 0);
}
}
static void prv_flash_erase_async(
uint32_t sector_addr, bool is_subsector, FlashOperationCompleteCb on_complete_cb,
void *context) {
uint32_t remaining_ms = prv_flash_erase_start(sector_addr, on_complete_cb,
context, is_subsector, 0);
if (remaining_ms) {
// Start timer that will periodically check for the erase to complete
new_timer_start(s_erase_poll_timer, remaining_ms, prv_flash_erase_timer_cb, NULL, 0);
}
}
static void prv_blocking_erase_complete(void *context, status_t status) {
PBL_ASSERT(PASSED(status), "Flash erase failure: %" PRId32, status);
}
static void prv_flash_erase_blocking(uint32_t sector_addr, bool is_subsector) {
uint32_t total_time_spent_waiting_ms = 0;
uint32_t remaining_ms = prv_flash_erase_start(
sector_addr, prv_blocking_erase_complete, NULL, is_subsector, 0);
while (remaining_ms) {
psleep(remaining_ms);
total_time_spent_waiting_ms += remaining_ms;
remaining_ms = prv_flash_erase_poll();
// check to see if the cb responsible for resuming erases should have run
// but is blocked. See PBL-25741 for details
uint32_t erase_suspend_time_remaining;
if (new_timer_scheduled(s_erase_suspend_timer, &erase_suspend_time_remaining) &&
(erase_suspend_time_remaining == 0)) {
prv_erase_suspend_timer_cb(NULL);
}
// An erase can take a long time, especially if the erase needs to be
// retried. Appease the watchdog so that it doesn't get angry when an
// erase takes >6 seconds.
//
// After a certain amount of time passes, stop kicking the watchdog. This is to handle a case
// where the erase never finishes or takes an unheard of amount of time to complete. Just let
// the watchdog kill us in this case.
static const uint32_t FLASH_ERASE_BLOCKING_TIMEOUT_MS = 5000;
if (total_time_spent_waiting_ms < FLASH_ERASE_BLOCKING_TIMEOUT_MS) {
#if IS_BIGBOARD
// Our bigboards have had a hard life and they have some fairly abused flash chips, and we
// run into 5+ second erases pretty regularly. We're not holding the flash lock while we're
// doing this, so other threads are allowed to use flash, but it's pretty common to hold
// other locks while waiting for a flash operation to complete, leading to other tasks
// triggering their task watchdogs before this erase completes. Let's kick all watchdogs
// instead. The downside to this is that it may take us longer to detect another thread is
// stuck, but we should still detect it eventually as long as we're not constantly erasing.
task_watchdog_bit_set_all();
#else
// Just kick the watchdog for the current task. This should give us more accurate watchdog
// behaviour and sealed watches haven't been abused as much and shouldn't have extremely
// long erase problems.
task_watchdog_bit_set(pebble_task_get_current());
#endif
}
}
}
void flash_erase_sector(uint32_t sector_addr,
FlashOperationCompleteCb on_complete_cb,
void *context) {
prv_flash_erase_async(sector_addr, false /* is_subsector */, on_complete_cb, context);
}
void flash_erase_subsector(uint32_t sector_addr,
FlashOperationCompleteCb on_complete_cb,
void *context) {
prv_flash_erase_async(sector_addr, true /* is_subsector */, on_complete_cb, context);
}
void flash_erase_sector_blocking(uint32_t sector_addr) {
prv_flash_erase_blocking(sector_addr, false /* is_subsector */);
}
void flash_erase_subsector_blocking(uint32_t subsector_addr) {
prv_flash_erase_blocking(subsector_addr, true /* is_subsector */);
}
void flash_enable_write_protection(void) {
flash_impl_enable_write_protection();
}
void flash_prf_set_protection(bool do_protect) {
status_t status;
mutex_lock(s_flash_lock);
if (do_protect) {
status = flash_impl_write_protect(
FLASH_REGION_SAFE_FIRMWARE_BEGIN,
(FLASH_REGION_SAFE_FIRMWARE_END - SECTOR_SIZE_BYTES));
} else {
status = flash_impl_unprotect();
}
PBL_ASSERT(PASSED(status), "flash_prf_set_protection failed: %" PRId32, status);
mutex_unlock(s_flash_lock);
}
#if 0
void flash_erase_bulk(void) {
mutex_lock(s_flash_lock);
flash_impl_erase_bulk_begin();
while (flash_impl_erase_is_in_progress()) {
psleep(10);
}
mutex_unlock(s_flash_lock);
}
#endif
void flash_sleep_when_idle(bool enable) {
// the S29VS flash automatically enters and exits standby
}
bool flash_get_sleep_when_idle(void) {
return false;
}
bool flash_is_initialized(void) {
return (s_flash_lock != NULL);
}
void flash_stop(void) {
if (!flash_is_initialized()) {
// Not yet initialized, nothing to do.
return;
}
mutex_lock(s_flash_lock);
if (s_erase.in_progress) {
new_timer_stop(s_erase_suspend_timer);
prv_erase_resume();
mutex_unlock(s_flash_lock);
while (__atomic_load_n(&s_erase.in_progress, __ATOMIC_SEQ_CST)) {
psleep(10);
}
}
}
void flash_switch_mode(FlashModeType mode) {
mutex_lock(s_flash_lock);
flash_impl_set_burst_mode(mode == FLASH_MODE_SYNC_BURST);
mutex_unlock(s_flash_lock);
}
uint32_t flash_get_sector_base_address(uint32_t flash_addr) {
return flash_impl_get_sector_base_address(flash_addr);
}
uint32_t flash_get_subsector_base_address(uint32_t flash_addr) {
return flash_impl_get_subsector_base_address(flash_addr);
}
void flash_power_down_for_stop_mode(void) {
flash_impl_enter_low_power_mode();
}
void flash_power_up_after_stop_mode(void) {
flash_impl_exit_low_power_mode();
}
bool flash_sector_is_erased(uint32_t sector_addr) {
return flash_impl_blank_check_sector(flash_impl_get_sector_base_address(sector_addr));
}
bool flash_subsector_is_erased(uint32_t sector_addr) {
return flash_impl_blank_check_subsector(flash_impl_get_subsector_base_address(sector_addr));
}
void flash_use(void) {
mutex_lock(s_flash_lock);
flash_impl_use();
mutex_unlock(s_flash_lock);
}
void flash_release_many(uint32_t num_locks) {
mutex_lock(s_flash_lock);
flash_impl_release_many(num_locks);
mutex_unlock(s_flash_lock);
}
#include "console/prompt.h"
void command_flash_unprotect(void) {
flash_impl_unprotect();
prompt_send_response("OK");
}

View file

@ -0,0 +1,83 @@
/*
* 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/flash.h"
#include "kernel/pbl_malloc.h"
#include "system/logging.h"
#include "util/crc32.h"
#include "util/legacy_checksum.h"
#include <stdint.h>
static size_t prv_allocate_crc_buffer(void **buffer) {
// Try to allocate a big buffer for reading flash data. If we can't,
// use a smaller one.
unsigned int chunk_size = 1024;
*buffer = kernel_malloc(chunk_size);
if (!*buffer) {
PBL_LOG(LOG_LEVEL_WARNING, "Insufficient memory for a large CRC buffer, going slow");
chunk_size = 128;
*buffer = kernel_malloc_check(chunk_size);
}
return chunk_size;
}
uint32_t flash_crc32(uint32_t flash_addr, uint32_t num_bytes) {
void *buffer;
unsigned int chunk_size = prv_allocate_crc_buffer(&buffer);
uint32_t crc = CRC32_INIT;
while (num_bytes > chunk_size) {
flash_read_bytes(buffer, flash_addr, chunk_size);
crc = crc32(crc, buffer, chunk_size);
num_bytes -= chunk_size;
flash_addr += chunk_size;
}
flash_read_bytes(buffer, flash_addr, num_bytes);
crc = crc32(crc, buffer, num_bytes);
kernel_free(buffer);
return crc;
}
uint32_t flash_calculate_legacy_defective_checksum(uint32_t flash_addr,
uint32_t num_bytes) {
void *buffer;
unsigned int chunk_size = prv_allocate_crc_buffer(&buffer);
LegacyChecksum checksum;
legacy_defective_checksum_init(&checksum);
while (num_bytes > chunk_size) {
flash_read_bytes(buffer, flash_addr, chunk_size);
legacy_defective_checksum_update(&checksum, buffer, chunk_size);
num_bytes -= chunk_size;
flash_addr += chunk_size;
}
flash_read_bytes(buffer, flash_addr, num_bytes);
legacy_defective_checksum_update(&checksum, buffer, num_bytes);
kernel_free(buffer);
return legacy_defective_checksum_finish(&checksum);
}

View file

@ -0,0 +1,143 @@
/*
* 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/flash.h"
#include "drivers/flash/flash_internal.h"
#include "flash_region/flash_region.h"
#include "services/common/new_timer/new_timer.h"
#include "system/passert.h"
#include "util/attributes.h"
#include "util/math.h"
#include "FreeRTOS.h"
#include "semphr.h"
#include <inttypes.h>
static SemaphoreHandle_t s_erase_mutex = NULL;
static struct FlashRegionEraseState {
uint32_t next_erase_addr;
uint32_t end_addr;
FlashOperationCompleteCb on_complete;
void *on_complete_context;
} s_erase_state;
static void prv_erase_next_async(void *ignored);
T_STATIC void prv_lock_erase_mutex(void);
T_STATIC void prv_unlock_erase_mutex(void);
#if !UNITTEST
void flash_erase_init(void) {
s_erase_mutex = xSemaphoreCreateBinary();
xSemaphoreGive(s_erase_mutex);
}
static void prv_lock_erase_mutex(void) {
xSemaphoreTake(s_erase_mutex, portMAX_DELAY);
}
static void prv_unlock_erase_mutex(void) {
xSemaphoreGive(s_erase_mutex);
}
#endif
static void prv_async_erase_done_cb(void *ignored, status_t result) {
if (PASSED(result) &&
s_erase_state.next_erase_addr < s_erase_state.end_addr) {
// Chain the next erase from a new callback to prevent recursion (and the
// potential for a stack overflow) if the flash_erase_sector calls the
// completion callback asynchronously.
if (!new_timer_add_work_callback(prv_erase_next_async, NULL)) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to enqueue callback; aborting erase");
prv_unlock_erase_mutex();
s_erase_state.on_complete(s_erase_state.on_complete_context, E_INTERNAL);
}
} else {
prv_unlock_erase_mutex();
s_erase_state.on_complete(s_erase_state.on_complete_context, result);
}
}
static void prv_erase_next_async(void *ignored) {
uint32_t addr = s_erase_state.next_erase_addr;
if ((addr & ~SECTOR_ADDR_MASK) == 0 &&
addr + SECTOR_SIZE_BYTES <= s_erase_state.end_addr) {
s_erase_state.next_erase_addr += SECTOR_SIZE_BYTES;
flash_erase_sector(addr, prv_async_erase_done_cb, NULL);
} else {
// Fall back to a subsector erase
s_erase_state.next_erase_addr += SUBSECTOR_SIZE_BYTES;
PBL_ASSERTN(s_erase_state.next_erase_addr <= s_erase_state.end_addr);
flash_erase_subsector(addr, prv_async_erase_done_cb, NULL);
}
}
void flash_erase_optimal_range(
uint32_t min_start, uint32_t max_start, uint32_t min_end, uint32_t max_end,
FlashOperationCompleteCb on_complete, void *context) {
PBL_ASSERTN(((min_start & (~SUBSECTOR_ADDR_MASK)) == 0) &&
((max_end & (~SUBSECTOR_ADDR_MASK)) == 0) &&
(min_start <= max_start) &&
(max_start <= min_end) &&
(min_end <= max_end));
// We want to erase the sector that starts immediately below max_start but
// after min_start. If no sector boundary exists between the two, we need to
// start erasing sectors after min_start and backfill with subsector erases.
int32_t sector_start = (max_start & SECTOR_ADDR_MASK);
int32_t subsector_start = (max_start & SUBSECTOR_ADDR_MASK);
if (sector_start < (int32_t) min_start) {
sector_start += SECTOR_SIZE_BYTES;
}
// We want to erase ending after min_end but before max_end. If that ends
// running past the end of max_end, we need to erase starting with the sector
// before and fill in with subsector erases.
int32_t sector_end = ((min_end - 1) & SECTOR_ADDR_MASK) + SECTOR_SIZE_BYTES;
int32_t subsector_end =
((min_end - 1) & SUBSECTOR_ADDR_MASK) + SUBSECTOR_SIZE_BYTES;
if (sector_end > (int32_t) max_end) {
sector_end -= SECTOR_SIZE_BYTES;
}
int32_t start_addr = MIN(sector_start, subsector_start);
int32_t end_addr = MAX(sector_end, subsector_end);
if (sector_start >= sector_end) {
// Can't erase any full sectors; just erase subsectors the whole way.
start_addr = subsector_start;
end_addr = subsector_end;
}
if (start_addr == end_addr) {
// Nothing to do!
on_complete(context, S_NO_ACTION_REQUIRED);
return;
}
prv_lock_erase_mutex();
s_erase_state = (struct FlashRegionEraseState) {
.next_erase_addr = start_addr,
.end_addr = end_addr,
.on_complete = on_complete,
.on_complete_context = context,
};
prv_erase_next_async(NULL);
}

View file

@ -0,0 +1,322 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stddef.h>
#include <stdint.h>
#include "system/status_codes.h"
//! Flash Low-Level API
//!
//! Unless otherwise specified, this API is non-reentrant. It is unsafe to
//! call a function in one thread while another function is being executed in a
//! second thread, and it is unsafe to call these functions from within a
//! flash_impl callback.
typedef uint32_t FlashAddress;
//! Initialize the low-level flash implementation and hardware into a known
//! state where it is ready to accept commands.
//!
//! This function configures microcontroller peripherals. It should be guarded
//! with periph_config_acquire_lock/periph_config_release_lock.
//!
//! @param coredump_mode True if we need this flash driver to not rely on any other system
//! services such as FreeRTOS being available because we're in the middle
//! of a core dump. This may result in slower operations.
status_t flash_impl_init(bool coredump_mode);
//! Enable or disable synchronous burst mode, if supported.
//!
//! Burst mode is disabled whenever \ref flash_impl_init is called.
//!
//! The result is undefined if this function is called while any other flash
//! operation is in progress.
status_t flash_impl_set_burst_mode(bool enable);
//! Return the base address of the sector overlapping the given address.
//!
//! This function is reentrant.
FlashAddress flash_impl_get_sector_base_address(FlashAddress addr);
//! Return the base address of the subsector overlapping the given address.
//!
//! This function is reentrant.
FlashAddress flash_impl_get_subsector_base_address(FlashAddress addr);
//! Query the flash hardware for its capacity in bytes.
size_t flash_impl_get_capacity(void);
//! Enter a low-power state.
//!
//! Once in a low-power mode, all operations may fail until
//! \ref flash_impl_exit_low_power_mode is called. This function is idempotent.
status_t flash_impl_enter_low_power_mode(void);
//! Exit a low-power state.
//!
//! Return the flash to a fully operational mode. This may be a time-intensive
//! operation. This function is idempotent.
status_t flash_impl_exit_low_power_mode(void);
//! Read data into a buffer.
//!
//! The result is undefined if this function is called while a write or erase is
//! in progress.
status_t flash_impl_read_sync(void *buffer, FlashAddress addr, size_t len);
//! Initiate a DMA-accelerated flash read.
//!
//! The caller must ensure that the DMA transfer will not be interfered with
//! by any clock changes or stoppages externally. (read: inhibit stop mode)
//!
//! This function will return immediately once the transfer has begun.
//! \ref flash_impl_on_read_dma_complete_from_isr will be called from an
//! interrupt context to signal that the transfer has completed. The effect of
//! calling flash_impl_read_dma_begin a second time while another DMA transfer
//! is currently in progress is undefined.
//!
//! The result is undefined if this function is called while a write or erase is
//! in progress.
status_t flash_impl_read_dma_begin(void *buffer, FlashAddress addr,
size_t len);
//! Called from an interrupt context when the DMA read has completed. It is
//! guaranteed that the call is made from an interrupt of low enough priority
//! that RTOS API calls are safe to use, and that it is a tail-call from the end
//! of the implementation's ISR (read: portEND_SWITCHING_ISR is permissible).
//!
//! @param result S_SUCCESS iff the read completed successfully.
extern void flash_impl_on_read_dma_complete_from_isr(status_t result);
//! If the flash part requires write protection to be explicitly enabled, enable it.
void flash_impl_enable_write_protection(void);
//! Write protect a region of flash. Only one region may be protected at any
//! given time.
//!
//! The result is undefined if this function is called while a write or erase is
//! in progress.
status_t flash_impl_write_protect(FlashAddress start_sector,
FlashAddress end_sector);
//! Remove write protection.
//!
//! The result is undefined if this function is called while a write or erase is
//! in progress.
status_t flash_impl_unprotect(void);
//! Write a page of bytes to flash.
//!
//! @param buffer The source buffer.
//! @param addr Destination flash address.
//! @param len Length to write.
//! @return The number of bytes that will be written to flash, assuming that the
//! write completes successfully, or a StatusCode error if there was an
//! error starting the write operation.
//!
//! Each call to flash_impl_write_page_begin begins a single flash write
//! operation, writing the maximum amount of data supported by the hardware in
//! a single operation. Multiple page writes may be required to write a complete
//! buffer to flash.
//!
//! Example usage:
//! \code
//! while (len) {
//! int written = flash_impl_write_page_begin(buffer, addr, len));
//! if (written < 0) {
//! // Handle error
//! }
//! status_t status;
//! while ((status = flash_impl_get_write_status()) == E_AGAIN) {
//! continue;
//! }
//! if (status != S_SUCCESS) {
//! // Handle error
//! }
//! buffer += written;
//! addr += written;
//! len -= written;
//! }
//! \endcode
//!
//! The result is undefined if this function is called while a read or erase is
//! in progress. It is an error to call this function while a write is
//! in progress or suspended.
int flash_impl_write_page_begin(const void *buffer, FlashAddress addr,
size_t len);
//! Poll the status of a flash page write.
//!
//! @return S_SUCCESS if the write has succeeded, E_ERROR if the write has
//! failed, E_BUSY if the write is still in progress or E_AGAIN if the
//! write is suspended.
status_t flash_impl_get_write_status(void);
//! Suspend an in-progress write so that reads and erases are permitted.
//!
//! @param addr The address passed to the \ref flash_impl_write_page_begin
//! call which initiated the write being suspended.
status_t flash_impl_write_suspend(FlashAddress addr);
//! Resume a previously-suspended write.
//!
//! @param addr The address passed to \ref flash_impl_write_suspend.
//!
//! The result is undefined if this function is called while a read or write is
//! in progress.
status_t flash_impl_write_resume(FlashAddress addr);
//! Erase the subsector which overlaps the given address.
//!
//! The result is undefined if this function is called while a read or write is
//! in progress. It is an error to call this function while an erase is
//! suspended.
status_t flash_impl_erase_subsector_begin(FlashAddress subsector_addr);
//! Erase the sector which overlaps the given address.
//!
//! The result is undefined if this function is called while a read or write is
//! in progress. It is an error to call this function while an erase is
//! suspended.
status_t flash_impl_erase_sector_begin(FlashAddress sector_addr);
//! Erase the entire flash.
//!
//! The result is undefined if this function is called while a read or write is
//! in progress. It is an error to call this function while an erase is
//! suspended.
status_t flash_impl_erase_bulk_begin(void);
//! Poll the status of a flash erase.
//!
//! @return S_SUCCESS if the erase has succeeded, E_ERROR if the erase has
//! failed, E_BUSY if the erase is still in progress or E_AGAIN if the
//! erase is suspended.
status_t flash_impl_get_erase_status(void);
//! Returns the typical duration of a subsector erase, in milliseconds.
//!
//! This function is reentrant.
uint32_t flash_impl_get_typical_subsector_erase_duration_ms(void);
//! Returns the typical duration of a sector erase, in milliseconds.
//!
//! This function is reentrant.
uint32_t flash_impl_get_typical_sector_erase_duration_ms(void);
//! Suspend an in-progress erase so that reads and writes are permitted.
//!
//! @param addr The sector address passed to the
//! \ref flash_impl_erase_subsector_begin or
//! \ref flash_impl_erase_sector_begin call which initiated the erase being
//! suspended.
//!
//! @return S_SUCCESS if the erase has been suspended, S_NO_ACTION_REQUIRED if
//! there was no erase in progress at the time, or an error code.
status_t flash_impl_erase_suspend(FlashAddress addr);
//! Resume a previously-suspended erase.
//!
//! @param addr The address passed to \ref flash_impl_erase_suspend.
//!
//! The result is undefined if this function is called while a read or write is
//! in progress.
status_t flash_impl_erase_resume(FlashAddress addr);
//! Check whether the subsector overlapping the specified address is blank
//! (reads as all 1's).
//!
//! @param addr An address within the subsector being checked.
//!
//! @return S_TRUE if blank, S_FALSE if any bit in the sector has been
//! programmed, or E_BUSY if another flash operation is in progress.
//!
//! This operation is hardware-accelerated if possible. This operation may not
//! be performed if any reads, writes, or erases are in progress or suspended,
//! and this operation cannot be suspended once initiated. The result is
//! undefined if any other flash operation is initiated or in progress while a
//! blank check operation is in progress.
//!
//! @warning This function may return S_TRUE on a subsector where an erase
//! operation was terminated prematurely. While such a subsector may
//! read back as blank, data loss may occur and writes may fail if the
//! subsector is not erased fully before it is written to.
status_t flash_impl_blank_check_subsector(FlashAddress addr);
//! Check whether the sector overlapping the specified address is blank (reads
//! as all 1's).
//!
//! @param addr An address within the sector being checked.
//!
//! @return S_TRUE if blank, S_FALSE if any bit in the sector has been
//! programmed, or E_BUSY if another flash operation is in progress.
//!
//! This operation is hardware-accelerated if possible. This operation may not
//! be performed if any reads, writes, or erases are in progress or suspended,
//! and this operation cannot be suspended once initiated. The result is
//! undefined if any other flash operation is initiated or in progress while a
//! blank check operation is in progress.
//!
//! @warning This function may return S_TRUE on a sector where an erase
//! operation was terminated prematurely. While such a sector may read
//! back as blank, data loss may occur and writes may fail if the
//! sector is not erased fully before it is written to.
status_t flash_impl_blank_check_sector(FlashAddress addr);
//! Save the address of an erase in progress to a nonvolatile location. The
//! erase address, along with the fact that an erase is in progress, must be
//! able to survive a system crash and reboot.
//!
//! @note Writing this data to the same flash array that is being erased is
//! almost certainly a bad idea.
//!
//! @param is_subsector True if the erase is a subsector.
//!
//! @param addr The address being erased.
//!
//! @return S_SUCCESS if the data was successfully stored.
status_t flash_impl_set_nvram_erase_status(bool is_subsector,
FlashAddress addr);
//! Save to a nonvolatile location the fact that no erase is in progress.
//!
//! @return S_SUCCESS if the status was successfully stored.
status_t flash_impl_clear_nvram_erase_status(void);
//! Retrieve the erase status previously set by
//! flash_impl_set_nvram_erase_status or flash_impl_clear_nvram_erase_status.
//!
//! @param [out] is_subsector The value of is_subsector passed to the most
//! most recent call to flash_impl_set_nvram_erase_status if the status was
//! not subsequently cleared by flash_impl_clear_nvram_erase_status. The
//! pointer should not be written to if the erase status was cleared.
//!
//! @param [out] addr The address passed to the most recent call to
//! flash_impl_set_nvram_erase_status if the status was not subsequently
//! cleared by flash_impl_clear_nvram_erase_status. The address should not be
//! written to if the erase status was cleared.
//!
//! @return S_TRUE if an erase was in progress; S_FALSE otherwise.
status_t flash_impl_get_nvram_erase_status(bool *is_subsector,
FlashAddress *addr);
void flash_impl_use(void);
void flash_impl_release(void);
void flash_impl_release_many(uint32_t num_locks);

View file

@ -0,0 +1,19 @@
/*
* 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.
*/
#pragma once
void flash_erase_init(void);

View file

@ -0,0 +1,236 @@
/*
* 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 <inttypes.h>
#include "drivers/flash.h"
#include "drivers/flash/micron_n25q/flash_private.h"
#include "drivers/watchdog.h"
#include "flash_region/flash_region.h"
#include "kernel/util/delay.h"
#include "util/math.h"
#include "kernel/core_dump_private.h"
//! We have our own flash driver for coredump support because it must not use
//! any FreeRTOS constructs & we want to keep it as simple as possible. In
//! addition we want the flexibility to be able to reset the flash driver to
//! get it into a working state
static void prv_flash_start_cmd(void) {
GPIO_ResetBits(FLASH_GPIO, FLASH_PIN_SCS);
}
static void prv_flash_end_cmd(void) {
GPIO_SetBits(FLASH_GPIO, FLASH_PIN_SCS);
// 50ns required between SCS going high and low again, so just delay here to be safe
delay_us(1);
}
static uint8_t prv_flash_send_and_receive_byte(uint8_t byte) {
// Ensure that there are no other write operations in progress
while (SPI_I2S_GetFlagStatus(FLASH_SPI, SPI_I2S_FLAG_TXE) == RESET) {
continue;
}
// Send the byte on the SPI bus
SPI_I2S_SendData(FLASH_SPI, byte);
// Wait for the response byte to be received
while (SPI_I2S_GetFlagStatus(FLASH_SPI, SPI_I2S_FLAG_RXNE) == RESET) {
continue;
}
// Return the byte
return SPI_I2S_ReceiveData(FLASH_SPI);
}
static uint8_t prv_flash_read_next_byte(void) {
uint8_t result = prv_flash_send_and_receive_byte(FLASH_CMD_DUMMY);
return result;
}
static void prv_flash_wait_for_write_bounded(volatile int cycles_to_wait) {
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_READ_STATUS_REG);
uint8_t status_register = 0;
do {
if (cycles_to_wait-- < 1) {
break;
}
status_register = prv_flash_read_next_byte();
} while (status_register & 0x1);
prv_flash_end_cmd();
}
// Init the flash hardware
void cd_flash_init(void) {
// Enable the SPI clock
RCC_APB2PeriphClockCmd(FLASH_SPI_CLOCK, ENABLE);
// Enable the GPIO clock
uint8_t idx = ((((uint32_t)FLASH_GPIO) - AHB1PERIPH_BASE) / 0x0400);
SET_BIT(RCC->AHB1ENR, (0x1 << idx));
// Init the flash hardware
flash_hw_init();
// Make sure we are not in deep sleep
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_WAKE);
prv_flash_end_cmd();
// See if we can successfully access the flash
// TODO: Will we successfully recover if the flash HW was left midstream in a command from
// before?
prv_flash_wait_for_write_bounded(64000000);
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_READ_ID);
uint32_t manufacturer = prv_flash_read_next_byte();
uint32_t type = prv_flash_read_next_byte();
uint32_t capacity = prv_flash_read_next_byte();
prv_flash_end_cmd();
// If we can't ready the flash info correctly, bail
CD_ASSERTN(manufacturer == 0x20 && type == 0xbb && (capacity >= 0x16));
}
static void prv_flash_write_enable(void) {
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_WRITE_ENABLE);
prv_flash_end_cmd();
}
static void prv_flash_send_24b_address(uint32_t start_addr) {
// Ensure the high bits are not set.
prv_flash_send_and_receive_byte((start_addr & 0xFF0000) >> 16);
prv_flash_send_and_receive_byte((start_addr & 0x00FF00) >> 8);
prv_flash_send_and_receive_byte((start_addr & 0x0000FF));
}
static void prv_flash_wait_for_write(void) {
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_READ_STATUS_REG);
uint8_t status_register = 0;
do {
status_register = prv_flash_read_next_byte();
} while (status_register & 0x1);
prv_flash_end_cmd();
}
static void prv_flash_write_page(const uint8_t* buffer, uint32_t start_addr, uint16_t buffer_size) {
// Ensure that we're not trying to write more data than a single page (256 bytes)
CD_ASSERTN(buffer_size <= FLASH_PAGE_SIZE);
CD_ASSERTN(buffer_size);
// Writing a zero-length buffer is a no-op.
if (buffer_size < 1) {
return;
}
prv_flash_write_enable();
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_PAGE_PROGRAM);
prv_flash_send_24b_address(start_addr);
while (buffer_size--) {
prv_flash_send_and_receive_byte(*buffer);
buffer++;
}
prv_flash_end_cmd();
prv_flash_wait_for_write();
}
void cd_flash_read_bytes(void* buffer_ptr, uint32_t start_addr, uint32_t buffer_size) {
uint8_t* buffer = buffer_ptr;
prv_flash_wait_for_write();
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_READ);
prv_flash_send_24b_address(start_addr);
while (buffer_size--) {
*buffer = prv_flash_read_next_byte();
buffer++;
}
prv_flash_end_cmd();
}
uint32_t cd_flash_write_bytes(const void* buffer_ptr, uint32_t start_addr, uint32_t buffer_size) {
CD_ASSERTN((start_addr + buffer_size <= CORE_DUMP_FLASH_END) &&
(int)start_addr >= CORE_DUMP_FLASH_START);
const uint8_t* buffer = buffer_ptr;
const uint32_t total_bytes = buffer_size;
uint32_t first_page_available_bytes = FLASH_PAGE_SIZE - (start_addr % FLASH_PAGE_SIZE);
uint32_t bytes_to_write = MIN(buffer_size, first_page_available_bytes);
while (bytes_to_write) {
prv_flash_write_page(buffer, start_addr, bytes_to_write);
start_addr += bytes_to_write;
buffer += bytes_to_write;
buffer_size -= bytes_to_write;
bytes_to_write = MIN(buffer_size, FLASH_PAGE_SIZE);
}
watchdog_feed();
return total_bytes;
}
static void prv_flash_erase_sector(uint32_t sector_addr) {
prv_flash_write_enable();
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_ERASE_SECTOR);
prv_flash_send_24b_address(sector_addr);
prv_flash_end_cmd();
prv_flash_wait_for_write();
}
static void prv_flash_erase_subsector(uint32_t sector_addr) {
prv_flash_write_enable();
prv_flash_start_cmd();
prv_flash_send_and_receive_byte(FLASH_CMD_ERASE_SUBSECTOR);
prv_flash_send_24b_address(sector_addr);
prv_flash_end_cmd();
prv_flash_wait_for_write();
}
// Erase a region comprised of 1 or more sub-sectors. This will erase sectors at a time if
// the address and size allow.
void cd_flash_erase_region(uint32_t start_addr, uint32_t total_bytes) {
CD_ASSERTN(((start_addr & SUBSECTOR_ADDR_MASK) == start_addr)
&& ((total_bytes & SUBSECTOR_ADDR_MASK) == total_bytes));
while (total_bytes > 0) {
if (((start_addr & SECTOR_ADDR_MASK) == start_addr) && (total_bytes >= SECTOR_SIZE_BYTES)) {
prv_flash_erase_sector(start_addr);
total_bytes -= SECTOR_SIZE_BYTES;
start_addr += SECTOR_SIZE_BYTES;
} else {
prv_flash_erase_subsector(start_addr);
total_bytes -= SUBSECTOR_SIZE_BYTES;
start_addr += SUBSECTOR_SIZE_BYTES;
}
watchdog_feed();
}
}

View file

@ -0,0 +1,700 @@
/*
* 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 <inttypes.h>
#include <stdbool.h>
#include <stdio.h>
#include "board/board.h"
#include "drivers/dma.h"
#include "drivers/flash.h"
#include "drivers/flash/micron_n25q/flash_private.h"
#include "kernel/util/stop.h"
#include "process_management/worker_manager.h"
#include "services/common/analytics/analytics.h"
#include "os/mutex.h"
#include "kernel/util/delay.h"
#include "system/logging.h"
#include "system/passert.h"
#include "util/math.h"
#include "FreeRTOS.h"
#include "semphr.h"
/*
* Each peripheral has a dma channel / stream it works with
* c.f. section 9.3.3 in stm32 reference manual
*/
/* RX DMA */
static DMA_Stream_TypeDef* FLASH_DMA_STREAM = DMA2_Stream0;
static const uint32_t FLASH_DMA_CHANNEL = DMA_Channel_3;
static const uint32_t FLASH_DMA_IRQn = DMA2_Stream0_IRQn;
static const uint32_t FLASH_DATA_REGISTER_ADDR = (uint32_t)&(SPI1->DR);
/* TX DMA */
static DMA_Stream_TypeDef* FLASH_TX_DMA_STREAM = DMA2_Stream3;
static const uint32_t FLASH_TX_DMA_CHANNEL = DMA_Channel_3;
static uint32_t analytics_read_count;
static uint32_t analytics_read_bytes_count;
static uint32_t analytics_write_bytes_count;
void analytics_external_collect_system_flash_statistics(void) {
// TODO: Add support back to tintin
}
void analytics_external_collect_app_flash_read_stats(void) {
analytics_set(ANALYTICS_APP_METRIC_FLASH_READ_COUNT, analytics_read_count, AnalyticsClient_App);
analytics_set(ANALYTICS_APP_METRIC_FLASH_READ_BYTES_COUNT, analytics_read_bytes_count, AnalyticsClient_App);
analytics_set(ANALYTICS_APP_METRIC_FLASH_WRITE_BYTES_COUNT, analytics_write_bytes_count, AnalyticsClient_App);
// The overhead cost of tracking whether each flash read was due to the foreground
// or background app is large, so the best we can do is to attribute to both of them
if (worker_manager_get_current_worker_md() != NULL) {
analytics_set(ANALYTICS_APP_METRIC_FLASH_READ_COUNT, analytics_read_count, AnalyticsClient_Worker);
analytics_set(ANALYTICS_APP_METRIC_FLASH_READ_BYTES_COUNT, analytics_read_bytes_count, AnalyticsClient_Worker);
analytics_set(ANALYTICS_APP_METRIC_FLASH_WRITE_BYTES_COUNT, analytics_write_bytes_count, AnalyticsClient_Worker);
}
analytics_read_count = 0;
analytics_read_bytes_count = 0;
analytics_write_bytes_count = 0;
}
struct FlashState {
bool enabled;
bool sleep_when_idle;
bool deep_sleep;
PebbleMutex * mutex;
SemaphoreHandle_t dma_semaphore;
} s_flash_state;
static void flash_deep_sleep_enter(void);
static void flash_deep_sleep_exit(void);
void assert_usable_state(void) {
PBL_ASSERTN(s_flash_state.mutex != 0);
}
static void enable_flash_dma_clock(void) {
// TINTINHACK: Rather than update this file to use the new DMA driver, just rely on the fact that
// this is the only consumer of DMA2.
periph_config_enable(DMA2, RCC_AHB1Periph_DMA2);
}
static void disable_flash_dma_clock(void) {
// TINTINHACK: Rather than update this file to use the new DMA driver, just rely on the fact that
// this is the only consumer of DMA2.
periph_config_disable(DMA2, RCC_AHB1Periph_DMA2);
}
static void setup_dma_read(uint8_t *buffer, int size) {
DMA_InitTypeDef dma_config;
DMA_DeInit(FLASH_DMA_STREAM);
DMA_DeInit(FLASH_TX_DMA_STREAM);
/* RX DMA config */
DMA_StructInit(&dma_config);
dma_config.DMA_Channel = FLASH_DMA_CHANNEL;
dma_config.DMA_DIR = DMA_DIR_PeripheralToMemory;
dma_config.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
dma_config.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
dma_config.DMA_Mode = DMA_Mode_Normal;
dma_config.DMA_PeripheralBaseAddr = FLASH_DATA_REGISTER_ADDR;
dma_config.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma_config.DMA_MemoryInc = DMA_MemoryInc_Enable;
dma_config.DMA_Priority = DMA_Priority_High;
dma_config.DMA_FIFOMode = DMA_FIFOMode_Disable;
dma_config.DMA_MemoryBurst = DMA_MemoryBurst_Single;
dma_config.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
dma_config.DMA_Memory0BaseAddr = (uint32_t)buffer;
dma_config.DMA_BufferSize = size;
DMA_Init(FLASH_DMA_STREAM, &dma_config);
/* TX DMA config */
dma_config.DMA_Channel = FLASH_TX_DMA_CHANNEL;
dma_config.DMA_DIR = DMA_DIR_MemoryToPeripheral;
dma_config.DMA_PeripheralBaseAddr = FLASH_DATA_REGISTER_ADDR;
dma_config.DMA_MemoryInc = DMA_MemoryInc_Disable;
dma_config.DMA_Priority = DMA_Priority_High;
dma_config.DMA_Memory0BaseAddr = (uint32_t)&FLASH_CMD_DUMMY;
dma_config.DMA_BufferSize = size;
DMA_Init(FLASH_TX_DMA_STREAM, &dma_config);
/* Setup DMA interrupts */
NVIC_InitTypeDef nvic_config;
nvic_config.NVIC_IRQChannel = FLASH_DMA_IRQn;
nvic_config.NVIC_IRQChannelPreemptionPriority = 0x0f;
nvic_config.NVIC_IRQChannelSubPriority = 0x00;
nvic_config.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_config);
DMA_ITConfig(FLASH_DMA_STREAM, DMA_IT_TC, ENABLE);
// enable the DMA stream to start the transfer
SPI_I2S_DMACmd(FLASH_SPI, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE);
}
static void do_dma_transfer(void) {
xSemaphoreTake(s_flash_state.dma_semaphore, portMAX_DELAY);
stop_mode_disable(InhibitorFlash);
DMA_Cmd(FLASH_DMA_STREAM, ENABLE);
DMA_Cmd(FLASH_TX_DMA_STREAM, ENABLE);
xSemaphoreTake(s_flash_state.dma_semaphore, portMAX_DELAY);
stop_mode_enable(InhibitorFlash);
xSemaphoreGive(s_flash_state.dma_semaphore);
}
void DMA2_Stream0_IRQHandler(void) {
if (DMA_GetITStatus(FLASH_DMA_STREAM, DMA_IT_TCIF3)) {
DMA_ClearITPendingBit(FLASH_DMA_STREAM, DMA_IT_TCIF3);
NVIC_DisableIRQ(FLASH_DMA_IRQn);
signed portBASE_TYPE was_higher_priority_task_woken = pdFALSE;
xSemaphoreGiveFromISR(s_flash_state.dma_semaphore, &was_higher_priority_task_woken);
portEND_SWITCHING_ISR(was_higher_priority_task_woken);
return; //notreached
}
}
static void flash_deep_sleep_enter(void) {
assert_usable_state();
if (!s_flash_state.deep_sleep) {
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_DEEP_SLEEP);
flash_end_cmd();
// guarantee we have actually transitioned to deep sleep
delay_us(5);
s_flash_state.deep_sleep = true;
}
}
static void flash_deep_sleep_exit(void) {
assert_usable_state();
if (s_flash_state.deep_sleep) {
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_WAKE);
flash_end_cmd();
// wait a sufficient amount of time to enter standby mode
// It appears violating these timing conditions can lead to
// random bit corruptions on flash writes!
delay_us(100);
s_flash_state.deep_sleep = false;
}
}
void handle_sleep_when_idle_begin(void) {
if (s_flash_state.sleep_when_idle) {
flash_deep_sleep_exit();
}
}
void flash_power_down_for_stop_mode(void) {
if (s_flash_state.sleep_when_idle) {
if (s_flash_state.enabled) {
enable_flash_spi_clock();
flash_deep_sleep_enter();
disable_flash_spi_clock();
}
}
}
void flash_power_up_after_stop_mode(void) {
// no need here as this platform doesn't support memory-mappable flash
}
uint32_t flash_get_sector_base_address(uint32_t addr) {
return addr & ~(SECTOR_SIZE_BYTES - 1);
}
// This simply issues a command to read a specific register
static uint8_t prv_flash_get_register(uint8_t command) {
flash_start_cmd();
flash_send_and_receive_byte(command);
uint8_t reg = flash_read_next_byte();
flash_end_cmd();
return reg;
}
// This will read the flag status register and check it for the SectorLockStatus flag
void prv_check_protection_flag() {
uint8_t flag_status_register = prv_flash_get_register(FLASH_CMD_READ_FLAG_STATUS_REG);
// assert if we found the flag to be enabled
PBL_ASSERTN(!(flag_status_register & N25QFlagStatusBit_SectorLockStatus));
}
// This will clear the protection flag error from a previous error.
// We call this because the error bits persist across reboots
static void prv_clear_flag_status_register(void) {
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_CLEAR_FLAG_STATUS_REG);
flash_end_cmd();
}
/**
* Write up to 1 page (256B) of data to flash. start_addr DOES NOT
* need to be paged aligned. When writing into the middle of a page
* (addr & 0xFFF > 0), overrunning the length of the page will cause
* the write to "wrap around" and will modify (i.e. corrupt) data
* stored before the starting address within the page.
*
*/
static void flash_write_page(const uint8_t* buffer, uint32_t start_addr, uint16_t buffer_size) {
// Ensure that we're not trying to write more data than a single page (256 bytes)
PBL_ASSERTN(buffer_size <= FLASH_PAGE_SIZE);
PBL_ASSERTN(buffer_size);
mutex_assert_held_by_curr_task(s_flash_state.mutex, true /* is_held */);
// Writing a zero-length buffer is a no-op.
if (buffer_size < 1) {
return;
}
flash_write_enable();
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_PAGE_PROGRAM);
flash_send_24b_address(start_addr);
while (buffer_size--) {
flash_send_and_receive_byte(*buffer);
buffer++;
}
flash_end_cmd();
flash_wait_for_write();
prv_check_protection_flag();
}
// Public interface
// From here on down, make sure you're taking the s_flash_state.mutex before doing anything to the SPI peripheral.
void flash_enable_write_protection(void) {
return;
}
void flash_lock(void) {
mutex_lock(s_flash_state.mutex);
}
void flash_unlock(void) {
mutex_unlock(s_flash_state.mutex);
}
bool flash_is_enabled(void) {
return (s_flash_state.enabled);
}
void flash_init(void) {
if (s_flash_state.mutex != 0) {
return; // Already initialized.
}
s_flash_state.mutex = mutex_create();
vSemaphoreCreateBinary(s_flash_state.dma_semaphore);
flash_lock();
enable_flash_spi_clock();
flash_start();
s_flash_state.enabled = true;
s_flash_state.sleep_when_idle = false;
// Assume that last time we shut down we were asleep. Come back out.
s_flash_state.deep_sleep = true;
flash_deep_sleep_exit();
prv_clear_flag_status_register();
disable_flash_spi_clock();
flash_unlock();
flash_whoami();
PBL_LOG_VERBOSE("Detected SPI Flash Size: %u bytes", flash_get_size());
}
void flash_stop(void) {
if (s_flash_state.mutex == NULL) {
return;
}
flash_lock();
s_flash_state.enabled = false;
flash_unlock();
}
void flash_read_bytes(uint8_t* buffer, uint32_t start_addr, uint32_t buffer_size) {
if (!buffer_size) {
return;
}
assert_usable_state();
flash_lock();
if (!s_flash_state.enabled) {
flash_unlock();
return;
}
analytics_read_count++;
analytics_read_bytes_count += buffer_size;
power_tracking_start(PowerSystemFlashRead);
enable_flash_spi_clock();
handle_sleep_when_idle_begin();
flash_wait_for_write();
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_READ);
flash_send_24b_address(start_addr);
// There is delay associated with setting up the stm32 dma, using FreeRTOS
// sempahores, handling ISRs, etc. Thus for short reads, the cost of using
// DMA is far more expensive than the read being performed. Reads greater
// than 34 was empirically determined to be the point at which using the DMA
// engine is advantageous
#if !defined(TARGET_QEMU)
const uint32_t num_reads_dma_cutoff = 34;
#else
// We are disabling DMA reads when running under QEMU for now because they are not reliable.
const uint32_t num_reads_dma_cutoff = buffer_size + 1;
#endif
if (buffer_size < num_reads_dma_cutoff) {
while (buffer_size--) {
*buffer = flash_read_next_byte();
buffer++;
}
} else {
enable_flash_dma_clock();
setup_dma_read(buffer, buffer_size);
do_dma_transfer();
disable_flash_dma_clock();
}
flash_end_cmd();
disable_flash_spi_clock();
power_tracking_stop(PowerSystemFlashRead);
flash_unlock();
}
void flash_write_bytes(const uint8_t* buffer, uint32_t start_addr, uint32_t buffer_size) {
if (!buffer_size) {
return;
}
PBL_ASSERTN((start_addr + buffer_size) <= BOARD_NOR_FLASH_SIZE);
assert_usable_state();
flash_lock();
if (!s_flash_state.enabled) {
flash_unlock();
return;
}
analytics_write_bytes_count += buffer_size;
power_tracking_start(PowerSystemFlashWrite);
enable_flash_spi_clock();
handle_sleep_when_idle_begin();
uint32_t first_page_available_bytes = FLASH_PAGE_SIZE - (start_addr % FLASH_PAGE_SIZE);
uint32_t bytes_to_write = MIN(buffer_size, first_page_available_bytes);
if (first_page_available_bytes < FLASH_PAGE_SIZE) {
PBL_LOG_VERBOSE("Address is not page-aligned; first write will be %"PRId32"B at address 0x%"PRIX32,
first_page_available_bytes, start_addr);
}
while (bytes_to_write) {
flash_write_page(buffer, start_addr, bytes_to_write);
start_addr += bytes_to_write;
buffer += bytes_to_write;
buffer_size -= bytes_to_write;
bytes_to_write = MIN(buffer_size, FLASH_PAGE_SIZE);
}
disable_flash_spi_clock();
power_tracking_stop(PowerSystemFlashWrite);
flash_unlock();
}
void flash_erase_subsector_blocking(uint32_t subsector_addr) {
assert_usable_state();
PBL_LOG(LOG_LEVEL_DEBUG, "Erasing subsector 0x%"PRIx32" (0x%"PRIx32" - 0x%"PRIx32")",
subsector_addr,
subsector_addr & SUBSECTOR_ADDR_MASK,
(subsector_addr & SUBSECTOR_ADDR_MASK) + SUBSECTOR_SIZE_BYTES);
flash_lock();
if (!s_flash_state.enabled) {
flash_unlock();
return;
}
analytics_inc(ANALYTICS_APP_METRIC_FLASH_SUBSECTOR_ERASE_COUNT, AnalyticsClient_CurrentTask);
power_tracking_start(PowerSystemFlashErase);
enable_flash_spi_clock();
handle_sleep_when_idle_begin();
flash_write_enable();
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_ERASE_SUBSECTOR);
flash_send_24b_address(subsector_addr);
flash_end_cmd();
flash_wait_for_write();
prv_check_protection_flag();
disable_flash_spi_clock();
power_tracking_stop(PowerSystemFlashErase);
flash_unlock();
}
void flash_erase_sector_blocking(uint32_t sector_addr) {
assert_usable_state();
PBL_LOG(LOG_LEVEL_DEBUG, "Erasing sector 0x%"PRIx32" (0x%"PRIx32" - 0x%"PRIx32")",
sector_addr,
sector_addr & SECTOR_ADDR_MASK,
(sector_addr & SECTOR_ADDR_MASK) + SECTOR_SIZE_BYTES);
if (flash_sector_is_erased(sector_addr)) {
PBL_LOG(LOG_LEVEL_DEBUG, "Sector %#"PRIx32" already erased", sector_addr);
return;
}
flash_lock();
if (!flash_is_enabled()) {
flash_unlock();
return;
}
power_tracking_start(PowerSystemFlashErase);
enable_flash_spi_clock();
handle_sleep_when_idle_begin();
flash_write_enable();
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_ERASE_SECTOR);
flash_send_24b_address(sector_addr);
flash_end_cmd();
flash_wait_for_write();
prv_check_protection_flag();
disable_flash_spi_clock();
power_tracking_stop(PowerSystemFlashErase);
flash_unlock();
}
// It is dangerous to leave this built in by default.
#if 0
void flash_erase_bulk(void) {
assert_usable_state();
flash_lock();
if (!s_flash_state.enabled) {
flash_unlock();
return;
}
flash_prf_set_protection(false);
power_tracking_start(PowerSystemFlashErase);
enable_flash_spi_clock();
handle_sleep_when_idle_begin();
flash_write_enable();
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_ERASE_BULK);
flash_end_cmd();
flash_wait_for_write();
flash_prf_set_protection(true);
disable_flash_spi_clock();
power_tracking_stop(PowerSystemFlashErase);
flash_unlock();
}
#endif
void flash_sleep_when_idle(bool enable) {
if (enable == s_flash_state.sleep_when_idle) {
return;
}
flash_lock();
if (!s_flash_state.enabled) {
flash_unlock();
return;
}
enable_flash_spi_clock();
s_flash_state.sleep_when_idle = enable;
if (enable) {
if (!s_flash_state.deep_sleep) {
flash_deep_sleep_enter();
}
} else {
if (s_flash_state.deep_sleep) {
flash_deep_sleep_exit();
}
}
disable_flash_spi_clock();
flash_unlock();
}
bool flash_get_sleep_when_idle(void) {
bool result;
flash_lock();
result = s_flash_state.deep_sleep;
flash_unlock();
return result;
}
void debug_flash_dump_registers(void) {
#ifdef PBL_LOG_ENABLED
flash_lock();
if (!s_flash_state.enabled) {
flash_unlock();
return;
}
enable_flash_spi_clock();
handle_sleep_when_idle_begin();
uint8_t status_register = prv_flash_get_register(FLASH_CMD_READ_STATUS_REG);
uint8_t lock_register = prv_flash_get_register(FLASH_CMD_READ_LOCK_REGISTER);
uint8_t flag_status_register = prv_flash_get_register(FLASH_CMD_READ_FLAG_STATUS_REG);
uint8_t nonvolatile_config_register =
prv_flash_get_register(FLASH_CMD_READ_NONVOLATILE_CONFIG_REGISTER);
uint8_t volatile_config_register =
prv_flash_get_register(FLASH_CMD_READ_VOLATILE_CONFIG_REGISTER);
disable_flash_spi_clock();
flash_unlock();
PBL_LOG(LOG_LEVEL_DEBUG, "Status Register: 0x%x", status_register);
PBL_LOG(LOG_LEVEL_DEBUG, "Lock Register: 0x%x", lock_register);
PBL_LOG(LOG_LEVEL_DEBUG, "Flag Status Register: 0x%x", flag_status_register);
PBL_LOG(LOG_LEVEL_DEBUG, "Nonvolatile Configuration Register: 0x%x", nonvolatile_config_register);
PBL_LOG(LOG_LEVEL_DEBUG, "Volatile Configuration Register: 0x%x", volatile_config_register);
#endif
}
bool flash_is_initialized(void) {
return (s_flash_state.mutex != 0);
}
size_t flash_get_size(void) {
uint32_t spi_flash_id = flash_whoami();
if (!check_whoami(spi_flash_id)) {
// Zero bytes is the best size to report if the flash is corrupted
return 0;
}
// capcity_megabytes = 2^(capacity in whoami)
uint32_t capacity = spi_flash_id & 0x000000FF;
// get the capacity of the flash in bytes
return 1 << capacity;
}
void flash_prf_set_protection(bool do_protect) {
assert_usable_state();
flash_lock();
if (!s_flash_state.enabled) {
flash_unlock();
return;
}
enable_flash_spi_clock();
handle_sleep_when_idle_begin();
flash_write_enable();
const uint32_t start_addr = FLASH_REGION_SAFE_FIRMWARE_BEGIN;
const uint32_t end_addr = FLASH_REGION_SAFE_FIRMWARE_END;
const uint8_t lock_bits = do_protect ? N25QLockBit_SectorWriteLock : 0;
for (uint32_t addr = start_addr; addr < end_addr; addr += SECTOR_SIZE_BYTES) {
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_WRITE_LOCK_REGISTER);
flash_send_24b_address(addr);
flash_send_and_receive_byte(lock_bits);
flash_end_cmd();
}
disable_flash_spi_clock();
flash_unlock();
}
void flash_erase_sector(uint32_t sector_addr,
FlashOperationCompleteCb on_complete_cb,
void *context) {
// TODO: implement nonblocking erase
flash_erase_sector_blocking(sector_addr);
on_complete_cb(context, S_SUCCESS);
}
void flash_erase_subsector(uint32_t sector_addr,
FlashOperationCompleteCb on_complete_cb,
void *context) {
// TODO: implement nonblocking erase
flash_erase_subsector_blocking(sector_addr);
on_complete_cb(context, S_SUCCESS);
}

View file

@ -0,0 +1,228 @@
/*
* 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/flash.h"
#include "kernel/util/delay.h"
#include "system/passert.h"
#include "util/units.h"
#include <inttypes.h>
#include <stdbool.h>
#include <stdio.h>
#include "drivers/flash/micron_n25q/flash_private.h"
void enable_flash_spi_clock(void) {
periph_config_enable(FLASH_SPI, FLASH_SPI_CLOCK);
}
void disable_flash_spi_clock(void) {
periph_config_disable(FLASH_SPI, FLASH_SPI_CLOCK);
}
// IMPORTANT: This method is also used by the core dump logic in order to re-initialize the flash hardware
// to prepare for writing the core dump. For this reason, it can NOT use any FreeRTOS functions, mess with
// the interrupt priority, primask, etc.
void flash_hw_init(void) {
// Connect PA5 to SPI1_SCLK
GPIO_PinAFConfig(FLASH_GPIO, GPIO_PinSource5, GPIO_AF_SPI1);
// Connect PA6 to SPI1_MISO
GPIO_PinAFConfig(FLASH_GPIO, GPIO_PinSource6, GPIO_AF_SPI1);
// Connect PA7 to SPI1_MOSI
GPIO_PinAFConfig(FLASH_GPIO, GPIO_PinSource7, GPIO_AF_SPI1);
GPIO_InitTypeDef gpio_cfg;
gpio_cfg.GPIO_OType = GPIO_OType_PP;
gpio_cfg.GPIO_PuPd = GPIO_PuPd_NOPULL;
gpio_cfg.GPIO_Mode = GPIO_Mode_AF;
gpio_cfg.GPIO_Speed = GPIO_Speed_50MHz;
gpio_cfg.GPIO_Pin = FLASH_PIN_MISO | FLASH_PIN_MOSI;
GPIO_Init(FLASH_GPIO, &gpio_cfg);
// Configure the SCLK pin to have a weak pull-down to put it in a known state
// when SCS is toggled
gpio_cfg.GPIO_PuPd = GPIO_PuPd_DOWN;
gpio_cfg.GPIO_Pin = FLASH_PIN_SCLK;
GPIO_Init(FLASH_GPIO, &gpio_cfg);
// Configure SCS to be controlled in software; pull up to high when inactive
gpio_cfg.GPIO_Mode = GPIO_Mode_OUT;
gpio_cfg.GPIO_Pin = FLASH_PIN_SCS;
gpio_cfg.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(FLASH_GPIO, &gpio_cfg);
// Set up a SPI bus on SPI1
SPI_InitTypeDef spi_cfg;
SPI_I2S_DeInit(FLASH_SPI);
spi_cfg.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi_cfg.SPI_Mode = SPI_Mode_Master;
spi_cfg.SPI_DataSize = SPI_DataSize_8b;
spi_cfg.SPI_CPOL = SPI_CPOL_Low;
spi_cfg.SPI_CPHA = SPI_CPHA_1Edge;
spi_cfg.SPI_NSS = SPI_NSS_Soft;
spi_cfg.SPI_BaudRatePrescaler = spi_find_prescaler(MHZ_TO_HZ(54), FLASH_SPI_CLOCK_PERIPH); // max read freq for the flash
spi_cfg.SPI_FirstBit = SPI_FirstBit_MSB;
spi_cfg.SPI_CRCPolynomial = 7;
SPI_Init(FLASH_SPI, &spi_cfg);
SPI_Cmd(FLASH_SPI, ENABLE);
}
void flash_start(void) {
periph_config_acquire_lock();
gpio_use(FLASH_GPIO);
// Init the hardware
flash_hw_init();
gpio_release(FLASH_GPIO);
periph_config_release_lock();
}
void flash_start_cmd(void) {
gpio_use(FLASH_GPIO);
GPIO_ResetBits(FLASH_GPIO, FLASH_PIN_SCS);
gpio_release(FLASH_GPIO);
}
void flash_end_cmd(void) {
gpio_use(FLASH_GPIO);
GPIO_SetBits(FLASH_GPIO, FLASH_PIN_SCS);
gpio_release(FLASH_GPIO);
// 50ns required between SCS going high and low again, so just delay here to be safe
delay_us(1);
}
uint8_t flash_send_and_receive_byte(uint8_t byte) {
// Ensure that there are no other write operations in progress
while (SPI_I2S_GetFlagStatus(FLASH_SPI, SPI_I2S_FLAG_TXE) == RESET);
// Send the byte on the SPI bus
SPI_I2S_SendData(FLASH_SPI, byte);
// Wait for the response byte to be received
while (SPI_I2S_GetFlagStatus(FLASH_SPI, SPI_I2S_FLAG_RXNE) == RESET);
// Return the byte
return SPI_I2S_ReceiveData(FLASH_SPI);
}
void flash_write_enable(void) {
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_WRITE_ENABLE);
flash_end_cmd();
}
void flash_send_24b_address(uint32_t start_addr) {
// Ensure the high bits are not set.
PBL_ASSERTN(!(start_addr & 0xFF000000));
flash_send_and_receive_byte((start_addr & 0xFF0000) >> 16);
flash_send_and_receive_byte((start_addr & 0x00FF00) >> 8);
flash_send_and_receive_byte((start_addr & 0x0000FF));
}
uint8_t flash_read_next_byte(void) {
uint8_t result = flash_send_and_receive_byte(FLASH_CMD_DUMMY);
return result;
}
void flash_wait_for_write_bounded(volatile int cycles_to_wait) {
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_READ_STATUS_REG);
uint8_t status_register = 0;
do {
if (cycles_to_wait-- < 1) {
break;
}
status_register = flash_read_next_byte();
} while (status_register & N25QStatusBit_WriteInProgress);
flash_end_cmd();
}
void flash_wait_for_write(void) {
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_READ_STATUS_REG);
uint8_t status_register = 0;
do {
status_register = flash_read_next_byte();
} while (status_register & N25QStatusBit_WriteInProgress);
flash_end_cmd();
}
bool flash_sector_is_erased(uint32_t sector_addr) {
const uint32_t bufsize = 128;
uint8_t buffer[bufsize];
sector_addr &= SECTOR_ADDR_MASK;
for (uint32_t offset = 0; offset < SECTOR_SIZE_BYTES; offset += bufsize) {
flash_read_bytes(buffer, sector_addr + offset, bufsize);
for (uint32_t i = 0; i < bufsize; i++) {
if (buffer[i] != 0xff) {
return false;
}
}
}
return true;
}
uint32_t flash_whoami(void) {
assert_usable_state();
flash_lock();
if (!flash_is_enabled()) {
flash_unlock();
return 0;
}
enable_flash_spi_clock();
handle_sleep_when_idle_begin();
flash_wait_for_write_bounded(64000000);
flash_start_cmd();
flash_send_and_receive_byte(FLASH_CMD_READ_ID);
uint32_t manufacturer = flash_read_next_byte();
uint32_t type = flash_read_next_byte();
uint32_t capacity = flash_read_next_byte();
flash_end_cmd();
disable_flash_spi_clock();
flash_unlock();
return ((manufacturer << 16) | (type << 8) | capacity);
}
bool check_whoami(uint32_t spi_flash_id) {
return spi_flash_id == EXPECTED_SPI_FLASH_ID_32MBIT ||
spi_flash_id == EXPECTED_SPI_FLASH_ID_64MBIT;
}
bool flash_is_whoami_correct(void) {
uint32_t spi_flash_id = flash_whoami();
return check_whoami(spi_flash_id);
}
void flash_switch_mode(FlashModeType mode) {
}

View file

@ -0,0 +1,115 @@
/*
* 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.
*/
#pragma once
#include "board/board.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/spi.h"
#include "flash_region/flash_region.h"
#include "system/passert.h"
#include "system/logging.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#include <mcu.h>
#include "debug/power_tracking.h"
/* GPIO */
static GPIO_TypeDef* const FLASH_GPIO = GPIOA;
/* SPI */
static SPI_TypeDef* const FLASH_SPI = SPI1;
static const uint32_t FLASH_SPI_CLOCK = RCC_APB2Periph_SPI1;
static const SpiPeriphClock FLASH_SPI_CLOCK_PERIPH = SpiPeriphClockAPB2;
/* Pin Defintions */
static const uint32_t FLASH_PIN_SCS = GPIO_Pin_4;
static const uint32_t FLASH_PIN_SCLK = GPIO_Pin_5;
static const uint32_t FLASH_PIN_MISO = GPIO_Pin_6;
static const uint32_t FLASH_PIN_MOSI = GPIO_Pin_7;
/* Flash SPI commands */
static const uint8_t FLASH_CMD_WRITE_ENABLE = 0x06;
static const uint8_t FLASH_CMD_WRITE_DISABLE = 0x04;
static const uint8_t FLASH_CMD_READ_STATUS_REG = 0x05;
static const uint8_t FLASH_CMD_READ_FLAG_STATUS_REG = 0x70;
static const uint8_t FLASH_CMD_CLEAR_FLAG_STATUS_REG = 0x50;
static const uint8_t FLASH_CMD_READ = 0x03;
static const uint8_t FLASH_CMD_READ_ID = 0x9F;
static const uint8_t FLASH_CMD_PAGE_PROGRAM = 0x02;
static const uint8_t FLASH_CMD_ERASE_SUBSECTOR = 0x20;
static const uint8_t FLASH_CMD_ERASE_SECTOR = 0xD8;
static const uint8_t FLASH_CMD_ERASE_BULK = 0xC7;
static const uint8_t FLASH_CMD_DEEP_SLEEP = 0xB9;
static const uint8_t FLASH_CMD_WAKE = 0xAB;
static const uint8_t FLASH_CMD_DUMMY = 0xA9;
static const uint8_t FLASH_CMD_WRITE_LOCK_REGISTER = 0xE5;
static const uint8_t FLASH_CMD_READ_LOCK_REGISTER = 0xE8;
static const uint8_t FLASH_CMD_READ_NONVOLATILE_CONFIG_REGISTER = 0xB5;
static const uint8_t FLASH_CMD_READ_VOLATILE_CONFIG_REGISTER = 0x85;
static const uint16_t FLASH_PAGE_SIZE = 0x100;
typedef enum N25QFlagStatusBit {
// Bit 0 is reserved
N25QFlagStatusBit_SectorLockStatus = (1 << 1),
N25QFlagStatusBit_ProgramSuspended = (1 << 2),
N25QFlagStatusBit_VppStatus = (1 << 3),
N25QFlagStatusBit_ProgramStatus = (1 << 4),
N25QFlagStatusBit_EraseStatus = (1 << 5),
N25QFlagStatusBit_EraseSuspended = (1 << 6),
N25QFlagStatusBit_DeviceReady = (1 << 7),
} N25QFlagStatusBit;
typedef enum N25QStatusBit {
N25QStatusBit_WriteInProgress = (1 << 0),
N25QStatusBit_WriteEnableLatch = (1 << 1),
N25QStatusBit_BlockProtect0 = (1 << 2),
N25QStatusBit_BlockProtect1 = (1 << 3),
N25QStatusBit_BlockProtect2 = (1 << 4),
N25QStatusBit_ProtectTopBottom = (1 << 5),
// Bit 6 is reserved
N25QStatusBit_StatusRegisterWrite = (1 << 7),
} N25QStatusBit;
typedef enum N25QLockBit {
N25QLockBit_SectorWriteLock = (1 << 0),
N25QLockBit_SectorLockDown = (1 << 1),
// Bits 2-7 are reserved
} N25QLockBit;
// Method shared with flash.c and the core dump logic in core_dump.c
void flash_hw_init(void);
void assert_usable_state(void);
void flash_lock(void);
void flash_unlock(void);
bool flash_is_enabled(void);
void handle_sleep_when_idle_begin(void);
void enable_flash_spi_clock(void);
void disable_flash_spi_clock(void);
void flash_start(void);
void flash_start_cmd(void);
void flash_end_cmd(void);
uint8_t flash_send_and_receive_byte(uint8_t byte);
void flash_write_enable(void);
void flash_send_24b_address(uint32_t start_addr);
uint8_t flash_read_next_byte(void);
void flash_wait_for_write_bounded(volatile int cycles_to_wait);
void flash_wait_for_write(void);
bool check_whoami(uint32_t spi_flash_id);
bool flash_is_whoami_correct(void);

View file

@ -0,0 +1,210 @@
/*
* 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 "board/board.h"
#include "drivers/flash/flash_impl.h"
#include "drivers/flash/qspi_flash.h"
#include "drivers/flash/qspi_flash_part_definitions.h"
#include "flash_region/flash_region.h"
#include "system/passert.h"
#include "system/status_codes.h"
#include "util/math.h"
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
static QSPIFlashPart QSPI_FLASH_PART = {
.instructions = {
.fast_read = 0x0B,
.fast_read_ddr = 0x0D,
.page_program = 0x02,
.erase_sector_4k = 0x20,
.erase_block_64k = 0xD8,
.write_enable = 0x06,
.write_disable = 0x04,
.read_status = 0x05,
.read_flag_status = 0x70,
.erase_suspend = 0x75,
.erase_resume = 0x7A,
.enter_low_power = 0xB9,
.exit_low_power = 0xAB,
.enter_quad_mode = 0x35,
.reset_enable = 0x66,
.reset = 0x99,
.qspi_id = 0xAF,
.block_lock = 0xE5,
.block_lock_status = 0xE8,
},
.status_bit_masks = {
.busy = 1 << 0,
.write_enable = 1 << 1,
},
.flag_status_bit_masks = {
.erase_suspend = 1 << 6,
},
.dummy_cycles = {
.fast_read = 10,
.fast_read_ddr = 8,
},
.block_lock = {
.has_lock_data = true,
.lock_data = 0x1,
.locked_check = 0x1,
},
.reset_latency_ms = 51,
.suspend_to_read_latency_us = 0,
.standby_to_low_power_latency_us = 3,
.low_power_to_standby_latency_us = 30,
.supports_fast_read_ddr = true,
#if BOARD_ROBERT_BB || BOARD_ROBERT_BB2 || BOARD_CUTTS_BB
.qspi_id_value = 0x19BB20,
.name = "MT25Q256",
#elif BOARD_ROBERT_EVT
.qspi_id_value = 0x18BB20,
.name = "MT25Q128",
#else
#error "Unsupported board"
#endif
};
bool flash_check_whoami(void) {
return qspi_flash_check_whoami(QSPI_FLASH);
}
FlashAddress flash_impl_get_sector_base_address(FlashAddress addr) {
return (addr & SECTOR_ADDR_MASK);
}
FlashAddress flash_impl_get_subsector_base_address(FlashAddress addr) {
return (addr & SUBSECTOR_ADDR_MASK);
}
void flash_impl_enable_write_protection(void) {
}
status_t flash_impl_write_protect(FlashAddress start_sector, FlashAddress end_sector) {
FlashAddress block_addr = start_sector;
while (block_addr <= end_sector) {
uint32_t block_size;
if (WITHIN(block_addr, SECTOR_SIZE_BYTES, BOARD_NOR_FLASH_SIZE - SECTOR_SIZE_BYTES - 1)) {
// Middle of flash has 64k lock units
block_addr = flash_impl_get_sector_base_address(block_addr);
block_size = SECTOR_SIZE_BYTES;
} else {
// Start and end of flash have 1 sector of 4k lock units
block_addr = flash_impl_get_subsector_base_address(block_addr);
block_size = SUBSECTOR_SIZE_BYTES;
}
const status_t sc = qspi_flash_lock_sector(QSPI_FLASH, block_addr);
if (FAILED(sc)) {
return sc;
}
block_addr += block_size;
}
return S_SUCCESS;
}
status_t flash_impl_unprotect(void) {
// No way to unprotect all of flash. This requires a full reset of the mt25q
qspi_flash_init(QSPI_FLASH, &QSPI_FLASH_PART, qspi_flash_is_in_coredump_mode(QSPI_FLASH));
return S_SUCCESS;
}
static void prv_set_high_drive_strength(void) {
// Match the impedance of the traces (~50 ohms) by configuring the drive strength of the data
// output pins on the MT25Q to the 45 ohm setting This avoids signal integreity issues. This is
// done by setting bits 2:0 in the "Enhanced Volatile Configuration Register" to 101b.
const uint8_t read_instruction = 0x65;
const uint8_t write_instruction = 0x61;
const uint8_t mask = 0x7;
const uint8_t value = 0x5;
qspi_flash_ll_set_register_bits(QSPI_FLASH, read_instruction, write_instruction, value, mask);
}
status_t flash_impl_init(bool coredump_mode) {
qspi_flash_init(QSPI_FLASH, &QSPI_FLASH_PART, coredump_mode);
#if BOARD_CUTTS_BB || BOARD_ROBERT_BB || BOARD_ROBERT_EVT
prv_set_high_drive_strength();
#endif
return S_SUCCESS;
}
status_t flash_impl_get_erase_status(void) {
return qspi_flash_is_erase_complete(QSPI_FLASH);
}
status_t flash_impl_erase_subsector_begin(FlashAddress subsector_addr) {
return qspi_flash_erase_begin(QSPI_FLASH, subsector_addr, true /* is_subsector */);
}
status_t flash_impl_erase_sector_begin(FlashAddress sector_addr) {
return qspi_flash_erase_begin(QSPI_FLASH, sector_addr, false /* !is_subsector */);
}
status_t flash_impl_erase_suspend(FlashAddress sector_addr) {
return qspi_flash_erase_suspend(QSPI_FLASH, sector_addr);
}
status_t flash_impl_erase_resume(FlashAddress sector_addr) {
qspi_flash_erase_resume(QSPI_FLASH, sector_addr);
return S_SUCCESS;
}
status_t flash_impl_read_sync(void *buffer_ptr, FlashAddress start_addr, size_t buffer_size) {
PBL_ASSERT(buffer_size > 0, "flash_impl_read_sync() called with 0 bytes to read");
qspi_flash_read_blocking(QSPI_FLASH, start_addr, buffer_ptr, buffer_size);
return S_SUCCESS;
}
int flash_impl_write_page_begin(const void *buffer, const FlashAddress start_addr, size_t len) {
return qspi_flash_write_page_begin(QSPI_FLASH, buffer, start_addr, len);
}
status_t flash_impl_get_write_status(void) {
return qspi_flash_get_write_status(QSPI_FLASH);
}
status_t flash_impl_enter_low_power_mode(void) {
qspi_flash_set_lower_power_mode(QSPI_FLASH, true);
return S_SUCCESS;
}
status_t flash_impl_exit_low_power_mode(void) {
qspi_flash_set_lower_power_mode(QSPI_FLASH, false);
return S_SUCCESS;
}
status_t flash_impl_set_burst_mode(bool burst_mode) {
// NYI
return S_SUCCESS;
}
status_t flash_impl_blank_check_sector(FlashAddress addr) {
return qspi_flash_blank_check(QSPI_FLASH, addr, false /* !is_subsector */);
}
status_t flash_impl_blank_check_subsector(FlashAddress addr) {
return qspi_flash_blank_check(QSPI_FLASH, addr, true /* is_subsector */);
}
uint32_t flash_impl_get_typical_sector_erase_duration_ms(void) {
return 150;
}
uint32_t flash_impl_get_typical_subsector_erase_duration_ms(void) {
return 50;
}

View file

@ -0,0 +1,223 @@
/*
* 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 "board/board.h"
#include "drivers/flash/flash_impl.h"
#include "drivers/flash/qspi_flash.h"
#include "drivers/flash/qspi_flash_part_definitions.h"
#include "flash_region/flash_region.h"
#include "system/passert.h"
#include "system/status_codes.h"
#include "system/version.h"
#include "util/math.h"
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
static QSPIFlashPart QSPI_FLASH_PART = {
.instructions = {
.fast_read = 0x0B,
.page_program = 0x02,
.erase_sector_4k = 0x20,
.erase_block_64k = 0xD8,
.write_enable = 0x06,
.write_disable = 0x04,
.read_status = 0x05,
.read_flag_status = 0x2B,
.erase_suspend = 0xB0,
.erase_resume = 0x30,
.enter_low_power = 0xB9,
.exit_low_power = 0xAB,
.enter_quad_mode = 0x35,
.reset_enable = 0x66,
.reset = 0x99,
.qspi_id = 0xAF,
.block_lock = 0x36,
.block_lock_status = 0x3C,
.block_unlock_all = 0x98,
.write_protection_enable = 0x68,
.read_protection_status = 0x2B,
},
.status_bit_masks = {
.busy = 1 << 0,
.write_enable = 1 << 1,
},
.flag_status_bit_masks = {
.erase_suspend = 1 << 3,
},
.dummy_cycles = {
.fast_read = 4,
},
.block_lock = {
.has_lock_data = false,
.locked_check = 0xff,
.protection_enabled_mask = (1 << 7),
},
.reset_latency_ms = 13,
.suspend_to_read_latency_us = 20,
.standby_to_low_power_latency_us = 10,
.low_power_to_standby_latency_us = 30,
.supports_fast_read_ddr = false,
.qspi_id_value = 0x3725c2,
.name = "MX25U64",
};
//! Any PRF built after this timestamp supports mx25u flash protection
#define MIN_PRF_TIMESTAMP_SUPPORTING_PROTECTION (1466531458)
//! True if the installed PRF version supports flash protection
static bool s_flash_protection_supported = false;
bool flash_check_whoami(void) {
return qspi_flash_check_whoami(QSPI_FLASH);
}
FlashAddress flash_impl_get_sector_base_address(FlashAddress addr) {
return (addr & SECTOR_ADDR_MASK);
}
FlashAddress flash_impl_get_subsector_base_address(FlashAddress addr) {
return (addr & SUBSECTOR_ADDR_MASK);
}
static bool prv_prf_supports_flash_protection(void) {
#if IS_BIGBOARD
// Bigboards should always exercise flash protection
return true;
#else
FirmwareMetadata prf;
if (!version_copy_recovery_fw_metadata(&prf)) {
return false;
}
return (prf.version_timestamp > MIN_PRF_TIMESTAMP_SUPPORTING_PROTECTION);
#endif
}
void flash_impl_enable_write_protection(void) {
s_flash_protection_supported = prv_prf_supports_flash_protection();
if (s_flash_protection_supported) {
// Ensure that write protection is enabled on the mx25u
if (qspi_flash_write_protection_enable(QSPI_FLASH) == S_SUCCESS) {
// after flash protection is enabled, full array is locked. Unlock it.
qspi_flash_unlock_all(QSPI_FLASH);
}
}
}
status_t flash_impl_write_protect(FlashAddress start_sector, FlashAddress end_sector) {
if (!s_flash_protection_supported) {
return S_SUCCESS; // If not supported, pretend protection succeeded.
}
FlashAddress block_addr = start_sector;
while (block_addr <= end_sector) {
uint32_t block_size;
if (WITHIN(block_addr, SECTOR_SIZE_BYTES, BOARD_NOR_FLASH_SIZE - SECTOR_SIZE_BYTES - 1)) {
// Middle of flash has 64k lock units
block_addr = flash_impl_get_sector_base_address(block_addr);
block_size = SECTOR_SIZE_BYTES;
} else {
// Start and end of flash have 1 sector of 4k lock units
block_addr = flash_impl_get_subsector_base_address(block_addr);
block_size = SUBSECTOR_SIZE_BYTES;
}
const status_t sc = qspi_flash_lock_sector(QSPI_FLASH, block_addr);
if (FAILED(sc)) {
return sc;
}
block_addr += block_size;
}
return S_SUCCESS;
}
status_t flash_impl_unprotect(void) {
return qspi_flash_unlock_all(QSPI_FLASH);
}
status_t flash_impl_init(bool coredump_mode) {
qspi_flash_init(QSPI_FLASH, &QSPI_FLASH_PART, coredump_mode);
qspi_flash_unlock_all(QSPI_FLASH);
return S_SUCCESS;
}
status_t flash_impl_get_erase_status(void) {
return qspi_flash_is_erase_complete(QSPI_FLASH);
}
status_t flash_impl_erase_subsector_begin(FlashAddress subsector_addr) {
return qspi_flash_erase_begin(QSPI_FLASH, subsector_addr, true /* is_subsector */);
}
status_t flash_impl_erase_sector_begin(FlashAddress sector_addr) {
return qspi_flash_erase_begin(QSPI_FLASH, sector_addr, false /* !is_subsector */);
}
status_t flash_impl_erase_suspend(FlashAddress sector_addr) {
return qspi_flash_erase_suspend(QSPI_FLASH, sector_addr);
}
status_t flash_impl_erase_resume(FlashAddress sector_addr) {
qspi_flash_erase_resume(QSPI_FLASH, sector_addr);
return S_SUCCESS;
}
status_t flash_impl_read_sync(void *buffer_ptr, FlashAddress start_addr, size_t buffer_size) {
PBL_ASSERT(buffer_size > 0, "flash_impl_read_sync() called with 0 bytes to read");
qspi_flash_read_blocking(QSPI_FLASH, start_addr, buffer_ptr, buffer_size);
return S_SUCCESS;
}
int flash_impl_write_page_begin(const void *buffer, const FlashAddress start_addr, size_t len) {
return qspi_flash_write_page_begin(QSPI_FLASH, buffer, start_addr, len);
}
status_t flash_impl_get_write_status(void) {
return qspi_flash_get_write_status(QSPI_FLASH);
}
status_t flash_impl_enter_low_power_mode(void) {
qspi_flash_set_lower_power_mode(QSPI_FLASH, true);
return S_SUCCESS;
}
status_t flash_impl_exit_low_power_mode(void) {
qspi_flash_set_lower_power_mode(QSPI_FLASH, false);
return S_SUCCESS;
}
status_t flash_impl_set_burst_mode(bool burst_mode) {
// NYI
return S_SUCCESS;
}
status_t flash_impl_blank_check_sector(FlashAddress addr) {
return qspi_flash_blank_check(QSPI_FLASH, addr, false /* !is_subsector */);
}
status_t flash_impl_blank_check_subsector(FlashAddress addr) {
return qspi_flash_blank_check(QSPI_FLASH, addr, true /* is_subsector */);
}
uint32_t flash_impl_get_typical_sector_erase_duration_ms(void) {
return 400;
}
uint32_t flash_impl_get_typical_subsector_erase_duration_ms(void) {
return 40;
}

View file

@ -0,0 +1,74 @@
/*
* 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/flash/flash_impl.h"
#include "system/passert.h"
#include "system/rtc_registers.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#include <stdbool.h>
#include <stdint.h>
// RTC backup registers are reset to zero on a cold boot (power up from a dead
// battery) so the value stored in the backup register corresponding to no erase
// in progress must also be zero. We need to use a nonzero value to store an
// erase to sector zero, so we can't simply store just the address.
//
// We want to store whether an erase is in progress (1 bit), whether the erase
// is for a sector or a subsector (1 bit), and the address being erased (32
// bits) in a single 32-bit RTC register. Since we can't magically compress 34
// bits into 32, we'll need to play some tricks. The address is going to almost
// certainly be less than 32 bits long; we aren't going to be using
// gigabyte-sized flash memories any time soon (at least not with this
// homegrown API), leaving bits free on the high end.
#define ERASE_IN_PROGRESS 0x80000000
#define ERASE_IS_SUBSECTOR 0x40000000
#define ERASE_FLAGS_MASK (ERASE_IN_PROGRESS | ERASE_IS_SUBSECTOR)
#define ERASE_ADDRESS_MASK 0x3FFFFFFF
status_t flash_impl_set_nvram_erase_status(bool is_subsector,
FlashAddress addr) {
PBL_ASSERTN((addr & ERASE_FLAGS_MASK) == 0); // "Flash address too large to store"
uint32_t reg = addr | ERASE_IN_PROGRESS;
if (is_subsector) {
reg |= ERASE_IS_SUBSECTOR;
}
RTC_WriteBackupRegister(RTC_BKP_FLASH_ERASE_PROGRESS, reg);
return S_SUCCESS;
}
status_t flash_impl_clear_nvram_erase_status(void) {
RTC_WriteBackupRegister(RTC_BKP_FLASH_ERASE_PROGRESS, 0);
return S_SUCCESS;
}
status_t flash_impl_get_nvram_erase_status(bool *is_subsector,
FlashAddress *addr) {
uint32_t reg = RTC_ReadBackupRegister(RTC_BKP_FLASH_ERASE_PROGRESS);
if (reg == 0) {
return S_FALSE;
}
*addr = reg & ERASE_ADDRESS_MASK;
*is_subsector = (reg & ERASE_IS_SUBSECTOR) != 0;
return S_TRUE;
}

View file

@ -0,0 +1,761 @@
/*
* 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 "qspi_flash.h"
#include "qspi_flash_definitions.h"
#include "board/board.h"
#include "drivers/flash/flash_impl.h"
#include "drivers/gpio.h"
#include "drivers/qspi.h"
#include "flash_region/flash_region.h"
#include "kernel/util/delay.h"
#include "kernel/util/sleep.h"
#include "mcu/cache.h"
#include "system/logging.h"
#include "system/passert.h"
#include "system/status_codes.h"
#include "util/math.h"
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#define FLASH_RESET_WORD_VALUE (0xffffffff)
static void prv_read_register(QSPIFlash *dev, uint8_t instruction, uint8_t *data, uint32_t length) {
qspi_indirect_read_no_addr(dev->qspi, instruction, 0, data, length, false /* !is_ddr */);
}
static void prv_write_cmd_no_addr(QSPIFlash *dev, uint8_t cmd) {
qspi_indirect_write_no_addr(dev->qspi, cmd, NULL, 0);
}
static void prv_write_enable(QSPIFlash *dev) {
prv_write_cmd_no_addr(dev, dev->state->part->instructions.write_enable);
// wait for writing to be enabled
qspi_poll_bit(dev->qspi, dev->state->part->instructions.read_status,
dev->state->part->status_bit_masks.write_enable, true /* set */, QSPI_NO_TIMEOUT);
}
static bool prv_check_whoami(QSPIFlash *dev) {
// The WHOAMI is 3 bytes
const uint32_t whoami_length = 3;
uint32_t read_whoami = 0;
prv_read_register(dev, dev->state->part->instructions.qspi_id, (uint8_t *)&read_whoami,
whoami_length);
if (read_whoami == dev->state->part->qspi_id_value) {
PBL_LOG(LOG_LEVEL_INFO, "Flash is %s", dev->state->part->name);
return true;
} else {
PBL_LOG(LOG_LEVEL_ERROR, "Flash isn't expected %s (whoami: 0x%"PRIx32")",
dev->state->part->name, read_whoami);
return false;
}
qspi_release(dev->qspi);
}
bool qspi_flash_check_whoami(QSPIFlash *dev) {
qspi_use(dev->qspi);
bool result = prv_check_whoami(dev);
qspi_release(dev->qspi);
return result;
}
static void prv_set_fast_read_ddr_enabled(QSPIFlash *dev, bool enabled) {
// If we're supposed to use DDR for fast read, make sure the part can support it
PBL_ASSERTN(!enabled || dev->state->part->supports_fast_read_ddr);
dev->state->fast_read_ddr_enabled = enabled;
}
bool qspi_flash_is_in_coredump_mode(QSPIFlash *dev) {
return dev->state->coredump_mode;
}
void qspi_flash_init(QSPIFlash *dev, QSPIFlashPart *part, bool coredump_mode) {
dev->state->part = part;
dev->state->coredump_mode = coredump_mode;
prv_set_fast_read_ddr_enabled(dev, dev->default_fast_read_ddr_enabled);
qspi_use(dev->qspi);
if (dev->reset_gpio.gpio) {
gpio_output_init(&dev->reset_gpio, GPIO_OType_PP, GPIO_Speed_2MHz);
gpio_output_set(&dev->reset_gpio, false);
}
// Must call quad_enable first, all commands are QSPI
qspi_indirect_write_no_addr_1line(dev->qspi, dev->state->part->instructions.enter_quad_mode);
// Reset the flash to stop any program's or erase in progress from before reboot
prv_write_cmd_no_addr(dev, dev->state->part->instructions.reset_enable);
prv_write_cmd_no_addr(dev, dev->state->part->instructions.reset);
if (coredump_mode) {
delay_us(dev->state->part->reset_latency_ms * 1000);
} else {
psleep(dev->state->part->reset_latency_ms);
}
// Return the flash to Quad SPI mode, all our commands are quad-spi and it'll just cause
// problems/bugs for someone if it comes back in single spi mode
qspi_indirect_write_no_addr_1line(dev->qspi, dev->state->part->instructions.enter_quad_mode);
if (!coredump_mode) {
prv_check_whoami(dev);
}
qspi_release(dev->qspi);
}
status_t qspi_flash_is_erase_complete(QSPIFlash *dev) {
qspi_use(dev->qspi);
uint8_t status_reg;
uint8_t flag_status_reg;
prv_read_register(dev, dev->state->part->instructions.read_status, &status_reg, 1);
prv_read_register(dev, dev->state->part->instructions.read_flag_status, &flag_status_reg, 1);
qspi_release(dev->qspi);
if (status_reg & dev->state->part->status_bit_masks.busy) {
return E_BUSY;
} else if (flag_status_reg & dev->state->part->flag_status_bit_masks.erase_suspend) {
return E_AGAIN;
} else {
return S_SUCCESS;
}
}
status_t qspi_flash_erase_begin(QSPIFlash *dev, uint32_t addr, bool is_subsector) {
uint8_t instruction;
if (is_subsector) {
instruction = dev->state->part->instructions.erase_sector_4k;
} else {
instruction = dev->state->part->instructions.erase_block_64k;
}
qspi_use(dev->qspi);
prv_write_enable(dev);
qspi_indirect_write(dev->qspi, instruction, addr, NULL, 0);
// wait for busy to be set indicating the erase has started
const uint32_t busy_timeout_us = 500;
const bool result = qspi_poll_bit(dev->qspi, dev->state->part->instructions.read_status,
dev->state->part->status_bit_masks.busy, true /* set */,
busy_timeout_us);
qspi_release(QSPI);
return result ? S_SUCCESS : E_ERROR;
}
status_t qspi_flash_erase_suspend(QSPIFlash *dev, uint32_t addr) {
qspi_use(dev->qspi);
uint8_t status_reg;
prv_read_register(dev, dev->state->part->instructions.read_status, &status_reg, 1);
if (!(status_reg & dev->state->part->status_bit_masks.busy)) {
// no erase in progress
qspi_release(QSPI);
return S_NO_ACTION_REQUIRED;
}
prv_write_cmd_no_addr(dev, dev->state->part->instructions.erase_suspend);
qspi_release(QSPI);
if (dev->state->part->suspend_to_read_latency_us) {
delay_us(dev->state->part->suspend_to_read_latency_us);
}
return S_SUCCESS;
}
void qspi_flash_erase_resume(QSPIFlash *dev, uint32_t addr) {
qspi_use(dev->qspi);
prv_write_cmd_no_addr(dev, dev->state->part->instructions.erase_resume);
// wait for the erase_suspend bit to be cleared
qspi_poll_bit(dev->qspi, dev->state->part->instructions.read_flag_status,
dev->state->part->flag_status_bit_masks.erase_suspend, false /* !set */,
QSPI_NO_TIMEOUT);
qspi_release(dev->qspi);
}
static void prv_get_fast_read_params(QSPIFlash *dev, uint8_t *instruction, uint8_t *dummy_cycles,
bool *is_ddr) {
if (dev->state->fast_read_ddr_enabled) {
*instruction = dev->state->part->instructions.fast_read_ddr;
*dummy_cycles = dev->state->part->dummy_cycles.fast_read_ddr;
*is_ddr = true;
} else {
*instruction = dev->state->part->instructions.fast_read;
*dummy_cycles = dev->state->part->dummy_cycles.fast_read;
*is_ddr = false;
}
}
static void prv_read_mmap_with_params(QSPIFlash *dev, uint32_t addr, void *buffer, uint32_t length,
uint8_t instruction, uint8_t dummy_cycles, bool is_ddr) {
qspi_mmap_start(dev->qspi, instruction, addr, dummy_cycles, length, is_ddr);
// Point the buffer at the QSPI region
memcpy(buffer, (uint32_t *)(QSPI_MMAP_BASE_ADDRESS + addr), length);
// stop memory mapped mode
qspi_mmap_stop(dev->qspi);
}
static void prv_read_mmap(QSPIFlash *dev, uint32_t addr, void *buffer, uint32_t length) {
uint8_t instruction;
uint8_t dummy_cycles;
bool is_ddr;
prv_get_fast_read_params(dev, &instruction, &dummy_cycles, &is_ddr);
prv_read_mmap_with_params(dev, addr, buffer, length, instruction,
dummy_cycles, is_ddr);
}
void qspi_flash_read_blocking(QSPIFlash *dev, uint32_t addr, void *buffer, uint32_t length) {
// TODO: Figure out what thresholds we should use when switching between memory mapping, DMA, &
// polling PBL-37438
bool should_use_dma = length > 128 && !dev->state->coredump_mode;
bool should_use_memmap = length > 128;
#if QSPI_DMA_DISABLE
// Known issues with some platforms, see PBL-37278 as an example
should_use_dma = false;
#endif
#if TARGET_QEMU
// QEMU doesn't yet support DMA or memory-mapping
should_use_dma = should_use_memmap = false;
#endif
qspi_use(dev->qspi);
uint8_t instruction;
uint8_t dummy_cycles;
bool is_ddr;
prv_get_fast_read_params(dev, &instruction, &dummy_cycles, &is_ddr);
if (should_use_dma) {
qspi_indirect_read_dma(dev->qspi, instruction, addr, dummy_cycles, buffer, length, is_ddr);
} else if (should_use_memmap) {
prv_read_mmap_with_params(dev, addr, buffer, length, instruction, dummy_cycles, is_ddr);
} else {
qspi_indirect_read(dev->qspi, instruction, addr, dummy_cycles, buffer, length, is_ddr);
}
qspi_release(dev->qspi);
}
int qspi_flash_write_page_begin(QSPIFlash *dev, const void *buffer, uint32_t addr,
uint32_t length) {
const uint32_t offset_in_page = addr % PAGE_SIZE_BYTES;
const uint32_t bytes_in_page = MIN(PAGE_SIZE_BYTES - offset_in_page, length);
qspi_use(dev->qspi);
prv_write_enable(dev);
qspi_indirect_write(dev->qspi, dev->state->part->instructions.page_program, addr, buffer,
bytes_in_page);
qspi_poll_bit(dev->qspi, dev->state->part->instructions.read_status,
dev->state->part->status_bit_masks.busy, false /* !set */, QSPI_NO_TIMEOUT);
qspi_release(dev->qspi);
return bytes_in_page;
}
status_t qspi_flash_get_write_status(QSPIFlash *dev) {
qspi_use(dev->qspi);
uint8_t status_reg;
prv_read_register(dev, dev->state->part->instructions.read_status, &status_reg, 1);
qspi_release(dev->qspi);
return (status_reg & dev->state->part->status_bit_masks.busy) ? E_BUSY : S_SUCCESS;
}
void qspi_flash_set_lower_power_mode(QSPIFlash *dev, bool active) {
qspi_use(dev->qspi);
uint8_t instruction;
uint32_t delay;
if (active) {
instruction = dev->state->part->instructions.enter_low_power;
delay = dev->state->part->standby_to_low_power_latency_us;
} else {
instruction = dev->state->part->instructions.exit_low_power;
delay = dev->state->part->low_power_to_standby_latency_us;
}
prv_write_cmd_no_addr(dev, instruction);
qspi_release(dev->qspi);
if (delay) {
delay_us(delay);
}
}
#if TARGET_QEMU
// While this works with normal hardware, it has a large stack requirment and I can't
// see a compelling reason to use it over the mmap blank check variant
static bool prv_blank_check_poll(QSPIFlash *dev, uint32_t addr, bool is_subsector) {
const uint32_t size_bytes = is_subsector ? SUBSECTOR_SIZE_BYTES : SECTOR_SIZE_BYTES;
const uint32_t BUF_SIZE_BYTES = 128;
const uint32_t BUF_SIZE_WORDS = BUF_SIZE_BYTES / sizeof(uint32_t);
uint32_t buffer[BUF_SIZE_WORDS];
for (uint32_t offset = 0; offset < size_bytes; offset += BUF_SIZE_BYTES) {
flash_impl_read_sync(buffer, addr + offset, BUF_SIZE_BYTES);
for (uint32_t i = 0; i < BUF_SIZE_WORDS; ++i) {
if (buffer[i] != FLASH_RESET_WORD_VALUE) {
return false;
}
}
}
return true;
}
#endif
static bool prv_blank_check_mmap(QSPIFlash *dev, uint32_t addr, bool is_subsector) {
const uint32_t size_bytes = is_subsector ? SUBSECTOR_SIZE_BYTES : SECTOR_SIZE_BYTES;
bool result = true;
uint8_t instruction;
uint8_t dummy_cycles;
bool is_ddr;
prv_get_fast_read_params(dev, &instruction, &dummy_cycles, &is_ddr);
qspi_mmap_start(dev->qspi, instruction, addr, dummy_cycles, size_bytes, is_ddr);
// Point the buffer at the QSPI region
uint32_t const volatile * const buffer = (uint32_t *)(QSPI_MMAP_BASE_ADDRESS + addr);
uint32_t size_words = size_bytes / sizeof(uint32_t);
for (uint32_t i = 0; i < size_words; ++i) {
if (buffer[i] != FLASH_RESET_WORD_VALUE) {
result = false;
break;
}
}
// stop memory mapped mode
qspi_mmap_stop(QSPI);
return result;
}
status_t qspi_flash_blank_check(QSPIFlash *dev, uint32_t addr, bool is_subsector) {
qspi_use(dev->qspi);
#if TARGET_QEMU
// QEMU doesn't support memory-mapping the FLASH
const bool result = prv_blank_check_poll(dev, addr, is_subsector);
#else
const bool result = prv_blank_check_mmap(dev, addr, is_subsector);
#endif
qspi_release(dev->qspi);
return result ? S_TRUE : S_FALSE;
}
void qspi_flash_ll_set_register_bits(QSPIFlash *dev, uint8_t read_instruction,
uint8_t write_instruction, uint8_t value, uint8_t mask) {
// make sure we're not trying to set any bits not within the mask
PBL_ASSERTN((value & mask) == value);
qspi_use(dev->qspi);
// first read the register
uint8_t reg_value;
prv_read_register(dev, read_instruction, &reg_value, 1);
// set the desired bits
reg_value = (reg_value & ~mask) | value;
// enable writing and write the register value
prv_write_cmd_no_addr(dev, dev->state->part->instructions.write_enable);
qspi_indirect_write_no_addr(dev->qspi, write_instruction, &reg_value, 1);
qspi_release(dev->qspi);
}
static bool prv_protection_is_enabled(QSPIFlash *dev) {
uint8_t status;
prv_read_register(dev, dev->state->part->instructions.read_protection_status, &status, 1);
return (status & dev->state->part->block_lock.protection_enabled_mask);
}
status_t qspi_flash_write_protection_enable(QSPIFlash *dev) {
#if TARGET_QEMU
return S_NO_ACTION_REQUIRED;
#endif
qspi_use(dev->qspi);
prv_write_enable(dev);
const bool already_enabled = prv_protection_is_enabled(dev);
if (already_enabled == false) {
PBL_LOG(LOG_LEVEL_INFO, "Enabling flash protection");
// Enable write protection
prv_write_cmd_no_addr(dev, dev->state->part->instructions.write_protection_enable);
// Poll busy status until done
qspi_poll_bit(dev->qspi, dev->state->part->instructions.read_status,
dev->state->part->status_bit_masks.busy, false /* !set */, QSPI_NO_TIMEOUT);
}
qspi_release(dev->qspi);
return (already_enabled) ? S_NO_ACTION_REQUIRED : S_SUCCESS;
}
status_t qspi_flash_lock_sector(QSPIFlash *dev, uint32_t addr) {
#if TARGET_QEMU
return S_SUCCESS;
#endif
qspi_use(dev->qspi);
prv_write_enable(dev);
// Lock or unlock the sector
const uint8_t instruction = dev->state->part->instructions.block_lock;
if (dev->state->part->block_lock.has_lock_data) {
qspi_indirect_write(dev->qspi, instruction, addr, &dev->state->part->block_lock.lock_data, 1);
} else {
qspi_indirect_write(dev->qspi, instruction, addr, NULL, 0);
}
// Poll busy status until done
qspi_poll_bit(dev->qspi, dev->state->part->instructions.read_status,
dev->state->part->status_bit_masks.busy, false /* !set */, QSPI_NO_TIMEOUT);
// Read lock status
uint8_t status;
qspi_indirect_read(dev->qspi, dev->state->part->instructions.block_lock_status,
addr, 0, &status, sizeof(status), false);
qspi_release(dev->qspi);
return (status == dev->state->part->block_lock.locked_check) ? S_SUCCESS : E_ERROR;
}
status_t qspi_flash_unlock_all(QSPIFlash *dev) {
#if TARGET_QEMU
return S_SUCCESS;
#endif
qspi_use(dev->qspi);
prv_write_enable(dev);
prv_write_cmd_no_addr(dev, dev->state->part->instructions.block_unlock_all);
qspi_release(dev->qspi);
return S_SUCCESS;
}
#if !RELEASE
#include "console/prompt.h"
#include "drivers/flash.h"
#include "kernel/pbl_malloc.h"
#include "system/profiler.h"
#include "util/size.h"
static bool prv_flash_read_verify(QSPIFlash *dev, int size, int offset) {
bool success = true;
char *buffer_dma_ptr = kernel_malloc_check(size + offset + 3);
char *buffer_pol = kernel_malloc_check(size + 3);
char *buffer_mmap = kernel_malloc_check(size + 3);
char *buffer_dma = buffer_dma_ptr + offset;
// The buffers need to be different, so when compared against each other we can make
// sure the write functions wrote the same thing.
memset(buffer_dma, 0xA5, size);
memset(buffer_pol, 0xCC, size);
memset(buffer_mmap, 0x33, size);
profiler_start();
prv_read_mmap(dev, 0, buffer_mmap, size);
profiler_stop();
uint32_t mmap_time = profiler_get_total_duration(true);
profiler_start();
uint8_t instruction;
uint8_t dummy_cycles;
bool is_ddr;
prv_get_fast_read_params(dev, &instruction, &dummy_cycles, &is_ddr);
qspi_indirect_read_dma(dev->qspi, instruction, 0, dummy_cycles, buffer_dma, size, is_ddr);
profiler_stop();
uint32_t dma_time = profiler_get_total_duration(true);
profiler_start();
qspi_indirect_read(dev->qspi, instruction, 0, dummy_cycles, buffer_pol, size, is_ddr);
profiler_stop();
uint32_t pol_time = profiler_get_total_duration(true);
if (memcmp(buffer_dma, buffer_pol, size) != 0) {
prompt_send_response("FAILURE: buffer_dma != buffer_pol");
success = false;
}
if (memcmp(buffer_dma, buffer_mmap, size) != 0) {
prompt_send_response("FAILURE: buffer_dma != buffer_mmap");
success = false;
}
const int buf_size = 64;
char buf[buf_size];
prompt_send_response_fmt(buf, buf_size, "Size: %d DMA: %"PRIu32 " POL: %"PRIu32 " MMP: %"PRIu32,
size, dma_time, pol_time, mmap_time);
kernel_free(buffer_dma_ptr);
kernel_free(buffer_pol);
kernel_free(buffer_mmap);
return success;
}
struct FlashReadTestValues {
int size;
int offset;
};
const struct FlashReadTestValues FLASH_READ_TEST_TABLE[] = {
{ .size = 1024, .offset = 0 },
{ .size = 1025, .offset = 0 },
{ .size = 1026, .offset = 0 },
{ .size = 1027, .offset = 0 },
{ .size = 1024, .offset = 1 },
{ .size = 1025, .offset = 2 },
{ .size = 1026, .offset = 3 },
{ .size = 4, .offset = 0 },
{ .size = 20, .offset = 0 },
{ .size = 60, .offset = 0 },
{ .size = 127, .offset = 0 },
{ .size = 128, .offset = 0 },
};
void command_flash_apicheck(const char *len_str) {
QSPIFlash *dev = QSPI_FLASH;
const int buf_size = 64;
char buf[buf_size];
int failures = 0;
int passes = 0;
profiler_init();
prompt_send_response("Check whoami");
if (!qspi_flash_check_whoami(dev)) {
++failures;
prompt_send_response("ERROR: Who am I failed");
} else {
++passes;
}
prompt_send_response("Enter low power mode");
flash_impl_enter_low_power_mode();
// WHOAMI should fail in low-power mode
prompt_send_response("Check whoami, should fail in low power mode");
if (qspi_flash_check_whoami(dev)) {
++failures;
prompt_send_response("ERROR: Who am I failed");
} else {
++passes;
}
prompt_send_response("Exit low power mode");
flash_impl_exit_low_power_mode();
prompt_send_response("Start flash_read_verify test");
qspi_use(QSPI);
const int final_size = atoi(len_str);
// If size is 0 run through a pre-defined table
if (final_size == 0) {
for (unsigned int i = 0; i < ARRAY_LENGTH(FLASH_READ_TEST_TABLE); ++i) {
bool result = prv_flash_read_verify(dev, FLASH_READ_TEST_TABLE[i].size,
FLASH_READ_TEST_TABLE[i].offset);
if (!result) {
++failures;
} else {
++passes;
}
}
} else {
if (prv_flash_read_verify(dev, final_size, 3)) {
++passes;
} else {
++failures;
prompt_send_response("ERROR: flash_read_verify failed");
}
}
qspi_release(QSPI);
bool was_busy = false;
// write a few bytes to the sector we're going to erase so it's not empty
uint8_t dummy_data = 0x55;
flash_write_bytes(&dummy_data, FLASH_REGION_FIRMWARE_SCRATCH_BEGIN, sizeof(dummy_data));
profiler_start();
status_t result = flash_impl_erase_sector_begin(FLASH_REGION_FIRMWARE_SCRATCH_BEGIN);
flash_impl_get_erase_status();
if (result == S_SUCCESS) {
while (flash_impl_get_erase_status() == E_BUSY) {
was_busy = true;
}
}
profiler_stop();
uint32_t duration = profiler_get_total_duration(true);
prompt_send_response_fmt(buf, buf_size, "Erase took: %"PRIu32, duration);
// Fash erases take at least ~100ms, if we're too short we probably didn't erase
const uint32_t min_erase_time = 10000;
if (result != S_SUCCESS) {
++failures;
prompt_send_response_fmt(buf, buf_size,
"FAILURE: erase did not report success %"PRIi32, result);
} else if (was_busy == false) {
++failures;
prompt_send_response("FAILURE: Flash never became busy, but we should be busy for 300ms.");
prompt_send_response("FAILURE: Flash probably never did an erase.");
} else if (duration < min_erase_time) {
++failures;
prompt_send_response("FAILURE: Flash erase completed way to quickly to have succeeded.");
} else {
++passes;
}
// must call blank_check_poll by hand, otherwise we'll get the dma version
profiler_start();
qspi_use(QSPI);
bool is_blank = qspi_flash_blank_check(QSPI_FLASH, FLASH_REGION_FIRMWARE_SCRATCH_BEGIN,
SUBSECTOR_SIZE_BYTES);
qspi_release(QSPI);
profiler_stop();
uint32_t blank = profiler_get_total_duration(true);
prompt_send_response_fmt(buf, buf_size, "Sector blank check via read took: %"PRIu32, blank);
if (is_blank != S_TRUE) {
++failures;
prompt_send_response("FAILURE: sector not blank!?!");
} else {
++passes;
}
profiler_start();
is_blank = flash_impl_blank_check_subsector(FLASH_REGION_FIRMWARE_SCRATCH_BEGIN);
profiler_stop();
blank = profiler_get_total_duration(true);
prompt_send_response_fmt(buf, buf_size, "Subsector blank check via read took: %"PRIu32,
blank);
if (is_blank != S_TRUE) {
++failures;
prompt_send_response("FAILURE: sector not blank!?!");
} else {
++passes;
}
if (failures == 0) {
prompt_send_response_fmt(buf, buf_size, "SUCCESS: run %d tests and all passeed", passes);
}
else {
prompt_send_response_fmt(buf, buf_size, "FAILED: run %d tests and %d failed",
passes + failures,
failures);
}
}
#endif
#if RECOVERY_FW
#include "console/prompt.h"
#include "drivers/flash.h"
#define SIGNAL_TEST_MAGIC_PATTERN (0xA5)
#define TEST_BUFFER_SIZE (1024)
static uint8_t s_test_buffer[TEST_BUFFER_SIZE];
static const uint32_t s_test_addr = FLASH_REGION_FIRMWARE_SCRATCH_END - SECTOR_SIZE_BYTES;
static bool s_signal_test_initialized;
void command_flash_signal_test_init(void) {
// just test one sector, which is probably less than the size of the region
// erase the sector
flash_erase_sector_blocking(s_test_addr);
// set the contents of the sector such that we will end up reading alternating 1s and 0s
memset(s_test_buffer, SIGNAL_TEST_MAGIC_PATTERN, sizeof(s_test_buffer));
flash_write_bytes(s_test_buffer, s_test_addr, sizeof(s_test_buffer));
QSPIFlash *dev = QSPI_FLASH;
// Ensure DDR is disabled for write check
prv_set_fast_read_ddr_enabled(dev, false);
uint8_t instruction;
uint8_t dummy_cycles;
bool is_ddr;
prv_get_fast_read_params(dev, &instruction, &dummy_cycles, &is_ddr);
PBL_ASSERTN(!is_ddr);
qspi_use(QSPI);
qspi_indirect_read(dev->qspi, instruction, s_test_addr, dummy_cycles, s_test_buffer,
sizeof(s_test_buffer), is_ddr);
prv_set_fast_read_ddr_enabled(dev, dev->default_fast_read_ddr_enabled);
qspi_release(QSPI);
bool success = true;
for (uint32_t i = 0; i < sizeof(s_test_buffer); ++i) {
if (s_test_buffer[i] != SIGNAL_TEST_MAGIC_PATTERN) {
success = false;
break;
}
}
if (success) {
prompt_send_response("Done!");
s_signal_test_initialized = true;
} else {
prompt_send_response("ERROR: Data read (SDR mode) did not match data written!");
}
}
void command_flash_signal_test_run(void) {
if (!s_signal_test_initialized) {
prompt_send_response("ERROR: 'flash signal test init' must be run first!");
return;
}
QSPIFlash *dev = QSPI_FLASH;
qspi_use(QSPI);
// set to DDR
prv_set_fast_read_ddr_enabled(dev, true);
// issue the read
uint8_t instruction;
uint8_t dummy_cycles;
bool is_ddr;
prv_get_fast_read_params(dev, &instruction, &dummy_cycles, &is_ddr);
PBL_ASSERTN(is_ddr);
qspi_indirect_read(dev->qspi, instruction, s_test_addr, dummy_cycles, s_test_buffer,
sizeof(s_test_buffer), is_ddr);
bool success = true;
for (uint32_t i = 0; i < sizeof(s_test_buffer); ++i) {
if (s_test_buffer[i] != SIGNAL_TEST_MAGIC_PATTERN) {
success = false;
break;
}
}
// set back to default mode
prv_set_fast_read_ddr_enabled(dev, dev->default_fast_read_ddr_enabled);
qspi_release(QSPI);
if (success) {
prompt_send_response("Ok");
} else {
prompt_send_response("ERROR: Read value didn't match!");
}
}
#endif

View file

@ -0,0 +1,85 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include "system/status_codes.h"
typedef const struct QSPIFlash QSPIFlash;
typedef const struct QSPIFlashPart QSPIFlashPart;
//! Initialize the QSPI flash
//! @param coredump_mode If true, don't use anything that might not be available mid-crash, such
//! as FreeRTOS calls or other system services.
void qspi_flash_init(QSPIFlash *dev, QSPIFlashPart *part, bool coredump_mode);
bool qspi_flash_is_in_coredump_mode(QSPIFlash *dev);
//! Check if the WHOAMI matches the expected value
bool qspi_flash_check_whoami(QSPIFlash *dev);
//! Check if an in-progress erase is complete
status_t qspi_flash_is_erase_complete(QSPIFlash *dev);
//! Begin an erase
status_t qspi_flash_erase_begin(QSPIFlash *dev, uint32_t addr, bool is_subsector);
//! Suspend an erase
status_t qspi_flash_erase_suspend(QSPIFlash *dev, uint32_t addr);
//! Resume a suspended erase
void qspi_flash_erase_resume(QSPIFlash *dev, uint32_t addr);
//! Performs a blocking read
void qspi_flash_read_blocking(QSPIFlash *dev, uint32_t addr, void *buffer, uint32_t length);
// Begins a write operation
int qspi_flash_write_page_begin(QSPIFlash *dev, const void *buffer, uint32_t addr, uint32_t length);
//! Gets the status of an in-progress write operation
status_t qspi_flash_get_write_status(QSPIFlash *dev);
//! Sets whether or not the QSPI flash is in low-power mode
void qspi_flash_set_lower_power_mode(QSPIFlash *dev, bool active);
//! Check whether a sector/subsector is blank
status_t qspi_flash_blank_check(QSPIFlash *dev, uint32_t addr, bool is_subsector);
//! Sets the values of the bits (masked by `mask`) in the register (read by `read_instruction` and
//! written via `write_instruction`) to `value`
void qspi_flash_ll_set_register_bits(QSPIFlash *dev, uint8_t read_instruction,
uint8_t write_instruction, uint8_t value, uint8_t mask);
//! Enable write/erase protection on the given QSPI flash part.
//! Requires the `write_protection_enable` and `read_protection_status` instructions.
//! Return value of the `read_protection_status` instruction is checked against
//! `block_lock.protection_enabled_mask` to test for success.
status_t qspi_flash_write_protection_enable(QSPIFlash *dev);
//! Lock the given sector from write/erase operations.
//! Sector locked with the `block_lock` instruction, and confirmed with `block_lock_status`
//! If the `block_lock` instruction requires extra data, `block_lock.has_lock_data`
//! and `block_lock.lock_data` can be used.
//! When checking `block_lock_status`, the returned status value is
//! compared against `block_lock.locked_check`
status_t qspi_flash_lock_sector(QSPIFlash *dev, uint32_t addr);
//! Unlock all sectors so they can be written/erased.
//! Operation is performed by the `block_unlock_all` instruction.
status_t qspi_flash_unlock_all(QSPIFlash *dev);

View file

@ -0,0 +1,37 @@
/*
* 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.
*/
#pragma once
#include "qspi_flash_part_definitions.h"
#include "board/board.h"
#include "drivers/qspi.h"
#include <stdint.h>
typedef struct QSPIFlashState {
QSPIFlashPart *part;
bool coredump_mode;
bool fast_read_ddr_enabled;
} QSPIFlashState;
typedef const struct QSPIFlash {
QSPIFlashState *state;
QSPIPort *qspi;
bool default_fast_read_ddr_enabled;
OutputConfig reset_gpio;
} QSPIFlash;

View file

@ -0,0 +1,73 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
typedef const struct QSPIFlashPart {
struct {
uint8_t fast_read;
uint8_t fast_read_ddr;
uint8_t page_program;
uint8_t erase_sector_4k;
uint8_t erase_block_64k;
uint8_t write_enable;
uint8_t write_disable;
uint8_t read_status;
uint8_t read_flag_status;
uint8_t erase_suspend;
uint8_t erase_resume;
uint8_t enter_low_power;
uint8_t exit_low_power;
uint8_t enter_quad_mode;
uint8_t exit_quad_mode;
uint8_t reset_enable;
uint8_t reset;
uint8_t qspi_id;
uint8_t block_lock;
uint8_t block_lock_status;
uint8_t block_unlock_all;
uint8_t write_protection_enable;
uint8_t read_protection_status;
} instructions;
struct {
uint8_t busy;
uint8_t write_enable;
} status_bit_masks;
struct {
uint8_t erase_suspend;
} flag_status_bit_masks;
struct {
uint8_t fast_read;
uint8_t fast_read_ddr;
} dummy_cycles;
struct {
bool has_lock_data; //<! true ifdata needs to be send along with the block_lock instruction
uint8_t lock_data; //<! The data to be sent on a block_lock command, if has_lock_data is true
uint8_t locked_check; //<! Value block_lock_status instruction should return if sector is locked
uint8_t protection_enabled_mask; //<! Mask read_protection_status instr to check if enabled
} block_lock;
uint32_t reset_latency_ms;
uint32_t suspend_to_read_latency_us;
uint32_t standby_to_low_power_latency_us;
uint32_t low_power_to_standby_latency_us;
bool supports_fast_read_ddr;
uint32_t qspi_id_value;
const char *name;
} QSPIFlashPart;

View file

@ -0,0 +1,936 @@
/*
* 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/flash/flash_impl.h"
#include <stdbool.h>
#include <stdint.h>
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "flash_region/flash_region.h"
#include "system/passert.h"
#include "system/logging.h"
#include "kernel/util/delay.h"
#include "util/math.h"
#include "util/size.h"
#include "util/units.h"
#define STM32F4_COMPATIBLE
#include <mcu.h>
//! This is the memory mapped region that's mapped to the parallel flash.
static const uintptr_t FMC_BANK_1_BASE_ADDRESS = 0x60000000;
//! This is the unit that we use for writing
static const uint32_t PAGE_SIZE_BYTES = 64;
//! Different commands we can send to the flash
typedef enum S29VSCommand {
S29VSCommand_WriteBufferLoad = 0x25,
S29VSCommand_BufferToFlash = 0x29,
S29VSCommand_EraseResume = 0x30,
S29VSCommand_SectorBlank = 0x33,
S29VSCommand_SectorLock = 0x60,
S29VSCommand_SectorLockRangeArg = 0x61,
S29VSCommand_ReadStatusRegister = 0x70,
S29VSCommand_ClearStatusRegister = 0x71,
S29VSCommand_EraseSetup = 0x80,
S29VSCommand_DeviceIDEntry = 0x90,
S29VSCommand_EraseSuspend = 0xB0,
S29VSCommand_ConfigureRegisterEntry = 0xD0,
S29VSCommand_SoftwareReset = 0xF0
} S29VSCommand;
//! Arguments to the S29VSCommand_EraseSetup command
typedef enum S29VSCommandEraseAguments {
S29VSCommandEraseAguments_ChipErase = 0x10,
S29VSCommandEraseAguments_SectorErase = 0x30
} S29VSCommandEraseAguments;
//! The bitset stored in the status register, see prv_read_status_register
typedef enum S29VSStatusBit {
S29VSStatusBit_BankStatus = (1 << 0),
S29VSStatusBit_SectorLockStatus = (1 << 1),
S29VSStatusBit_ProgramSuspended = (1 << 2),
// Bit 3 is reserved
S29VSStatusBit_ProgramStatus = (1 << 4),
S29VSStatusBit_EraseStatus = (1 << 5),
S29VSStatusBit_EraseSuspended = (1 << 6),
S29VSStatusBit_DeviceReady = (1 << 7),
} S29VSStatusBit;
static const uint16_t SPANSION_MANUFACTURER_ID = 0x01;
static const uint16_t MACRONIX_MANUFACTURER_ID = 0xc2;
static const GPIO_InitTypeDef s_default_at_flash_cfg = {
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
};
static void prv_issue_command_argument(FlashAddress sector_address, uint16_t cmd_arg);
static void prv_issue_command(FlashAddress sector_address, S29VSCommand cmd);
// puts gpios into or out of analog to save power when idle/in use respectively
static void prv_flash_idle_gpios(bool enable_gpios) {
static bool gpios_idled = false;
if (gpios_idled == enable_gpios) {
return;
}
gpios_idled = enable_gpios;
gpio_use(GPIOB);
gpio_use(GPIOD);
gpio_use(GPIOE);
GPIO_InitTypeDef gpio_init;
if (enable_gpios) {
gpio_init = s_default_at_flash_cfg;
} else {
gpio_init = (GPIO_InitTypeDef) {
.GPIO_Mode = GPIO_Mode_AN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_PuPd = GPIO_PuPd_NOPULL
};
}
// leave RESET_N and CE: they need to retain their state
// Configure the rest as analog inputs to save as much power as possible
// D2 - Reset - GPIO Reset line
// D7 - FMC CE - FMC Chip Enable
gpio_init.GPIO_Pin = GPIO_Pin_7;
GPIO_Init(GPIOB, &gpio_init);
gpio_init.GPIO_Pin = GPIO_Pin_All & (~GPIO_Pin_2) & (~GPIO_Pin_7);
GPIO_Init(GPIOD, &gpio_init);
gpio_init.GPIO_Pin = GPIO_Pin_All & (~GPIO_Pin_0) & (~GPIO_Pin_1);
GPIO_Init(GPIOE, &gpio_init);
gpio_release(GPIOE);
gpio_release(GPIOD);
gpio_release(GPIOB);
}
static uint32_t s_num_flash_uses = 0;
void flash_impl_use(void) {
if (s_num_flash_uses == 0) {
periph_config_enable(FMC_Bank1, RCC_AHB3Periph_FMC); // FIXME
prv_flash_idle_gpios(true);
}
s_num_flash_uses++;
}
void flash_impl_release_many(uint32_t num_locks) {
PBL_ASSERTN(s_num_flash_uses >= num_locks);
s_num_flash_uses -= num_locks;
if (s_num_flash_uses == 0) {
periph_config_disable(FMC_Bank1, RCC_AHB3Periph_FMC); // FIXME
}
}
void flash_impl_release(void) {
flash_impl_release_many(1);
}
static uint16_t flash_s29vs_read_short(FlashAddress addr) {
return *((__IO uint16_t*)(FMC_BANK_1_BASE_ADDRESS + addr));
}
FlashAddress flash_impl_get_sector_base_address(FlashAddress addr) {
if (addr < BOTTOM_BOOT_REGION_END) {
return addr & ~(BOTTOM_BOOT_SECTOR_SIZE - 1);
}
return addr & ~(SECTOR_SIZE_BYTES - 1);
}
FlashAddress flash_impl_get_subsector_base_address(FlashAddress addr) {
return flash_impl_get_sector_base_address(addr);
}
static uint8_t prv_read_status_register(FlashAddress sector_base_addr) {
prv_issue_command(sector_base_addr, S29VSCommand_ReadStatusRegister);
return flash_s29vs_read_short(sector_base_addr);
}
static uint8_t prv_poll_for_ready(FlashAddress sector_base_addr) {
// TODO: We should probably just assert if this takes too long
uint8_t status;
while (((status = prv_read_status_register(sector_base_addr)) &
S29VSStatusBit_DeviceReady) == 0) {
delay_us(10);
}
return (status);
}
//! Issue the second part of a two-cycle command. This is not merged with the
//! prv_issue_command as not all commands have an argument.
//!
//! @param sector_address The address of the start of the sector to write the command to.
//! @param cmd_arg The command argument to write.
static void prv_issue_command_argument(FlashAddress sector_address, uint16_t cmd_arg) {
// The offset in the sector we write the second part of commands to. Note that this is a 16-bit
// word aligned address as opposed to a byte address.
static const uint32_t COMMAND_ARGUMENT_ADDRESS = 0x2AA;
((__IO uint16_t*) (FMC_BANK_1_BASE_ADDRESS + sector_address))[COMMAND_ARGUMENT_ADDRESS] = cmd_arg;
}
//! @param sector_address The address of the start of the sector to write the command to.
//! @param cmd The command to write.
static void prv_issue_command(FlashAddress sector_address, S29VSCommand cmd) {
// The offset in the sector we write the first part of commands to. Note that this is a 16-bit
// word aligned address as opposed to a byte address.
static const uint32_t COMMAND_ADDRESS = 0x555;
((__IO uint16_t*) (FMC_BANK_1_BASE_ADDRESS + sector_address))[COMMAND_ADDRESS] = cmd;
}
static void prv_software_reset(void) {
prv_issue_command(0, S29VSCommand_SoftwareReset);
}
// Note: If this command has been executed at least once, all sectors are
// locked. They then must be unlocked before and relocked after each program
// operation (i.e write or erase). The chip only allows for one sector to be
// unlocked at any given time. For sector ranges which have been protected using
// the "Sector Lock Range Command", this function will have no effect.
static void prv_allow_write_if_sector_is_not_protected(bool lock, uint32_t sector_addr) {
prv_issue_command(0, S29VSCommand_SectorLock);
prv_issue_command_argument(0, S29VSCommand_SectorLock);
int lock_flag = (lock ? 0 : 1) << 7; // set A6 to 0 to lock and 1 to unlock
((__IO uint16_t*) (FMC_BANK_1_BASE_ADDRESS + sector_addr + lock_flag))[0] =
S29VSCommand_SectorLock;
}
static uint16_t prv_read_manufacturer_id(void) {
// Issue the DeviceIDEntry command to change to the ID-CFI Address Map. This means that reading from the bank will
// give us ID-CFI information instead of the normal flash contents. See Table 11.2 (ID/CFI Data) for all the
// content you can read here. Reset the state afterwards to return to the default address map.
flash_impl_use();
prv_issue_command(0, S29VSCommand_DeviceIDEntry);
uint16_t result = flash_s29vs_read_short(0x0);
prv_software_reset();
flash_impl_release();
return result;
}
static uint16_t prv_read_configuration_register(void) {
prv_issue_command(0, S29VSCommand_ConfigureRegisterEntry);
uint16_t result = flash_s29vs_read_short(0x0);
prv_software_reset();
return result;
}
static void prv_write_configuration_register(uint16_t data) {
// See section 5.8.1 of data sheet for command sequence
prv_issue_command(0, S29VSCommand_ConfigureRegisterEntry);
// Cycle 1: SA+Address 555h & Data 25h
// Cycle 2: SA+Address 2AAh & Data 00h
// Cycle 3: SA+Address X00h & PD
// Cycle 4: SA+ Address 555h & Data 29h
prv_issue_command(0, S29VSCommand_WriteBufferLoad);
prv_issue_command_argument(0, 0);
((__IO uint16_t*) (FMC_BANK_1_BASE_ADDRESS))[0] = data;
prv_issue_command(0, S29VSCommand_BufferToFlash);
prv_software_reset();
}
// Use the "Sector Lock Range Command" (section 8.2 of data sheet) to block
// writes or erases to the PRF image residing on the flash. The only way to undo
// this is to issue a HW reset or pull power
static void prv_flash_protect_range(uint32_t start_sector, uint32_t end_sector) {
PBL_ASSERTN(start_sector <= end_sector);
flash_impl_use();
prv_issue_command(0, S29VSCommand_SectorLock);
prv_issue_command_argument(0, S29VSCommand_SectorLock);
start_sector = flash_impl_get_sector_base_address(start_sector);
end_sector = flash_impl_get_sector_base_address(end_sector);
((__IO uint16_t*) (FMC_BANK_1_BASE_ADDRESS + start_sector))[0] =
S29VSCommand_SectorLockRangeArg;
((__IO uint16_t*) (FMC_BANK_1_BASE_ADDRESS + end_sector))[0] =
S29VSCommand_SectorLockRangeArg;
flash_impl_release();
}
void flash_s29vs_hw_init(void) {
// Configure the reset pin (D2)
GPIO_InitTypeDef gpio_init = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
};
GPIO_Init(GPIOD, &gpio_init);
GPIO_WriteBit(GPIOD, GPIO_Pin_2, Bit_SET);
// Configure pins relating to the FMC peripheral (30 pins!)
// B7 - FMC AVD - FMC Address Valid aka Latch
// D0-D1, D8-D15, E2-15 - FMC A, AD - FMC Address and Address/Data lines
// D2 - Reset - GPIO Reset line
// D3 - FMC CLK
// D4 - FMC OE - FMC Output Enable
// D5 - FMC WE - FMC Write Enable
// D6 - FMC RDY - FMC Ready line
// D7 - FMC CE - FMC Chip Enable
GPIO_PinAFConfig(GPIOB, GPIO_PinSource7, GPIO_AF_FMC);
gpio_init = s_default_at_flash_cfg;
gpio_init.GPIO_Pin = GPIO_Pin_7;
GPIO_Init(GPIOB, &gpio_init);
for (uint8_t pin_source = 0; pin_source < 16; ++pin_source) {
if (pin_source == 2) {
continue;
}
GPIO_PinAFConfig(GPIOD, pin_source, GPIO_AF_FMC);
}
gpio_init.GPIO_Pin = GPIO_Pin_All & (~GPIO_Pin_2);
GPIO_Init(GPIOD, &gpio_init);
for (uint8_t pin_source = 2; pin_source < 16; ++pin_source) {
GPIO_PinAFConfig(GPIOE, pin_source, GPIO_AF_FMC);
}
gpio_init.GPIO_Pin = GPIO_Pin_All & (~GPIO_Pin_0) & (~GPIO_Pin_1);
GPIO_Init(GPIOE, &gpio_init);
// We have configured the pins, lets perform a full HW reset to put the chip
// in a good state
GPIO_WriteBit(GPIOD, GPIO_Pin_2, Bit_RESET);
delay_us(10); // only needs to be 50ns according to data sheet
GPIO_WriteBit(GPIOD, GPIO_Pin_2, Bit_SET);
delay_us(30); // need 200ns + 10us before CE can be pulled low
flash_impl_set_burst_mode(false);
}
static void prv_flash_reset(void) {
s_num_flash_uses = 0;
gpio_use(GPIOB);
gpio_use(GPIOD);
gpio_use(GPIOE);
flash_impl_use();
flash_s29vs_hw_init();
flash_impl_release();
gpio_release(GPIOE);
gpio_release(GPIOD);
gpio_release(GPIOB);
}
void flash_impl_enable_write_protection(void) {
}
// Protects start_sector - end_sector, inclusive, from any kind of program
// operation
status_t flash_impl_write_protect(FlashAddress start_sector,
FlashAddress end_sector) {
prv_flash_reset();
prv_flash_protect_range(start_sector, end_sector);
return S_SUCCESS;
}
status_t flash_impl_unprotect(void) {
// The only way to undo sector protection is to pull power from the chip or
// issue a hardware reset
prv_flash_reset();
return S_SUCCESS;
}
status_t flash_impl_init(bool coredump_mode) {
// Don't need to do anything to enable coredump mode.
prv_flash_reset();
return S_SUCCESS;
}
status_t flash_impl_get_erase_status(void) {
flash_impl_use();
uint8_t status = prv_read_status_register(0);
flash_impl_release();
if ((status & S29VSStatusBit_DeviceReady) == 0) return E_BUSY;
if ((status & S29VSStatusBit_EraseSuspended) != 0) return E_AGAIN;
if ((status & S29VSStatusBit_EraseStatus) != 0) return E_ERROR;
return S_SUCCESS;
}
status_t flash_impl_erase_subsector_begin(FlashAddress subsector_addr) {
return flash_impl_erase_sector_begin(subsector_addr);
}
status_t flash_impl_erase_sector_begin(FlashAddress sector_addr) {
status_t result = E_UNKNOWN;
// FIXME: We should just assert that the address is already aligned. If
// someone is depending on this behaviour without already knowing the range
// that's being erased they're going to have a bad time. This will probably
// cause some client fallout though, so tackle this later.
sector_addr = flash_impl_get_sector_base_address(sector_addr);
flash_impl_use();
prv_issue_command(sector_addr, S29VSCommand_ClearStatusRegister);
// Some sanity checks
{
status_t error = S_SUCCESS;
const uint8_t sr = prv_read_status_register(sector_addr);
if ((sr & S29VSStatusBit_DeviceReady) == 0) {
// Another operation is already in progress.
error = E_BUSY;
} else if (sr & S29VSStatusBit_EraseSuspended) {
// Cannot program while another program operation is suspended.
error = E_INVALID_OPERATION;
}
if (FAILED(error)) {
result = error;
goto done;
}
}
prv_allow_write_if_sector_is_not_protected(false, sector_addr);
prv_issue_command(sector_addr, S29VSCommand_EraseSetup);
prv_issue_command_argument(sector_addr,
S29VSCommandEraseAguments_SectorErase);
prv_allow_write_if_sector_is_not_protected(true, sector_addr);
// Check the status register to make sure that the erase has started.
const uint8_t sr = prv_read_status_register(sector_addr);
if ((sr & S29VSStatusBit_DeviceReady) == 0) {
// Program or erase operation in progress. Is it in the current bank?
result = ((sr & S29VSStatusBit_BankStatus) == 0)? S_SUCCESS : E_BUSY;
} else {
// Operation hasn't started. Something is wrong.
if (sr & S29VSStatusBit_SectorLockStatus) {
// Sector is write-protected.
result = E_INVALID_OPERATION;
} else if (sr & S29VSStatusBit_EraseStatus) {
// Erase failed for some reason.
result = E_ERROR;
} else {
// The erase has either completed in the time between starting the erase
// and polling the status register, or the erase was never started. The
// former case could be due to a context switch at the worst time and
// subsequent task starvation, or being run in QEMU. The latter could be
// due to a software bug or hardware failure. It would be possible to tell
// the two situations apart by performing a blank check, but that takes
// more time than a nonblocking erase should require. Let the upper layers
// verify that the erase succeeded if they care about it.
result = S_SUCCESS;
}
}
done:
flash_impl_release();
return result;
}
status_t flash_impl_erase_suspend(FlashAddress sector_addr) {
status_t status = E_INTERNAL;
sector_addr = flash_impl_get_sector_base_address(sector_addr);
flash_impl_use();
const uint8_t sr = prv_read_status_register(sector_addr);
// Is an operation in progress?
if ((sr & S29VSStatusBit_DeviceReady) != 0) {
// No erase in progress to suspend. Maybe the erase completed before this
// call.
status = S_NO_ACTION_REQUIRED;
} else if ((sr & S29VSStatusBit_BankStatus) != 0) {
// Operation is in a different bank than the given address.
status = E_INVALID_ARGUMENT;
} else {
// All clear.
prv_issue_command(sector_addr, S29VSCommand_EraseSuspend);
if (prv_poll_for_ready(sector_addr) & S29VSStatusBit_EraseSuspended) {
status = S_SUCCESS;
} else {
// The erase must have completed between the status register read and
// the EraseSuspend command.
status = S_NO_ACTION_REQUIRED;
}
}
flash_impl_release();
return status;
}
status_t flash_impl_erase_resume(FlashAddress sector_addr) {
status_t status = E_INTERNAL;
sector_addr = flash_impl_get_sector_base_address(sector_addr);
flash_impl_use();
uint8_t sr = prv_read_status_register(sector_addr);
if ((sr & S29VSStatusBit_DeviceReady) != 0 &&
(sr & S29VSStatusBit_EraseSuspended) != 0) {
prv_issue_command(sector_addr, S29VSCommand_EraseResume);
status = S_SUCCESS;
} else {
// Device busy or no suspended erase to resume.
status = E_INVALID_OPERATION;
}
flash_impl_release();
return status;
}
// It is dangerous to leave this built in by default.
#if 0
status_t flash_impl_erase_bulk_begin(void) {
flash_s29vs_use();
prv_issue_command(0, S29VSCommand_EraseSetup);
prv_issue_command_argument(0, S29VSCommandEraseAguments_ChipErase);
flash_s29vs_release();
}
#endif
static void prv_read_words_pio(uint16_t* buffer, uint16_t* flash_data_region,
uint32_t num_words) {
for (uint32_t words_read = 0; words_read < num_words; words_read++) {
buffer[words_read] = flash_data_region[words_read];
}
}
// Currently this implementation reads halfwords at a time (16-bits). Burst
// length is currently 1 for synchronous reads. This can be optimized in future
// to do larger burst sizes and/or unrolling larger transfer sizes into 32-bit
// reads.
status_t flash_impl_read_sync(void *buffer_ptr, FlashAddress start_addr,
size_t buffer_size) {
uint8_t *buffer = buffer_ptr;
flash_impl_use();
uint32_t flash_data_addr = (FMC_BANK_1_BASE_ADDRESS + start_addr);
bool odd_start_addr = ((start_addr % 2) == 1);
uint32_t bytes_read = 0;
uint16_t* buff_ptr = (uint16_t *)&buffer[bytes_read];
if (odd_start_addr) {
// read first byte into a temporary buffer but read from source on aligned word boundary
uint16_t temp_buffer = *(__IO uint16_t *)(flash_data_addr-1);
buffer[bytes_read++] = (uint8_t)((temp_buffer >> 8) & 0xFF);
}
// At this point, flash_data_addr is now halfword aligned
buff_ptr = (uint16_t *)&buffer[bytes_read];
bool odd_buff_addr = ((((uint32_t)buff_ptr) % 2) == 1);
if (buffer_size - bytes_read >= 2) {
// if at least one halfword to read
if (!odd_buff_addr) {
// Both flash_data_addr and buffer are aligned
uint32_t num_words = (buffer_size - bytes_read) / 2;
prv_read_words_pio(buff_ptr, (uint16_t*)(flash_data_addr + bytes_read), num_words);
bytes_read += num_words*2;
} else {
// Not aligned - read into temporary buffer and copy over
__IO uint16_t *flash_data_region = (__IO uint16_t*)(flash_data_addr + bytes_read);
uint32_t num_words = (buffer_size - bytes_read) / 2;
for (uint32_t words_read = 0; words_read < num_words; words_read++) {
uint16_t temp_buffer = flash_data_region[words_read];
buffer[bytes_read++] = (uint8_t)(temp_buffer & 0xFF);
buffer[bytes_read++] = (uint8_t)((temp_buffer >> 8) & 0xFF);
}
}
}
buff_ptr = (uint16_t *)&buffer[bytes_read];
// See if there are any remaining bytes left - at this point - flash_data_addr is still halfword aligned
if (buffer_size - bytes_read == 1) {
uint16_t temp_buffer = *(__IO uint16_t *)(flash_data_addr + bytes_read);
buffer[bytes_read++] = (uint8_t)(temp_buffer & 0xFF);
} else if (buffer_size - bytes_read != 0) {
// Should not reach here
PBL_LOG(LOG_LEVEL_DEBUG, "Invalid data length read");
}
flash_impl_release();
return S_SUCCESS;
}
int flash_impl_write_page_begin(const void *vp_buffer,
const FlashAddress start_addr, size_t len) {
if (!len) {
return E_INVALID_ARGUMENT;
}
const uint8_t *buffer = vp_buffer;
// Flash write transactions can only write one page at a time, where each
// page is 64 bytes in size. Split up our transactions into pages and then
// write one page.
const uint32_t offset_in_page = start_addr % PAGE_SIZE_BYTES;
const uint32_t bytes_in_page = MIN(PAGE_SIZE_BYTES - offset_in_page, len);
// We're only allowed to write whole 16-bit words during a write operation.
// Therefore we'll need to pad out our write if it's not perfectly aligned at
// the start or the end.
int num_shorts = bytes_in_page / 2;
// 4 cases
// Perfectly aligned - No additional writes
// Unaligned start, even length - Need to pad both ends
// Unaligned start, odd length - Pad the start
// Aligned start, odd length - Pad the end
if (start_addr & 0x1 || bytes_in_page & 0x1) {
++num_shorts;
}
const FlashAddress sector_addr =
flash_impl_get_sector_base_address(start_addr);
flash_impl_use();
prv_issue_command(sector_addr, S29VSCommand_ClearStatusRegister);
// Some sanity checks
{
status_t error = S_SUCCESS;
const uint8_t sr = prv_read_status_register(sector_addr);
if ((sr & S29VSStatusBit_DeviceReady) == 0) {
// Another operation is already in progress.
error = E_BUSY;
} else if (sr & S29VSStatusBit_ProgramSuspended) {
// Cannot program while another program operation is suspended.
error = E_INVALID_OPERATION;
}
if (FAILED(error)) {
flash_impl_release();
return error;
}
}
prv_allow_write_if_sector_is_not_protected(false, sector_addr);
prv_issue_command(sector_addr, S29VSCommand_WriteBufferLoad);
prv_issue_command_argument(sector_addr, num_shorts - 1);
// We're now ready to write the words. Subsequent writes to the sector will
// actually write the data through to the write buffer.
__IO uint16_t *flash_write_dest = (__IO uint16_t*)
(FMC_BANK_1_BASE_ADDRESS + (start_addr & ~0x1));
uint32_t bytes_remaining = bytes_in_page;
// Handle leading byte
if (start_addr & 0x1) {
// Handle a buffer with an unaligned start. Write 0xff for the first byte
// since flash can only flip ones to zeros, and no data will be lost.
const uint16_t first_short_value = 0xFF | ((*buffer) << 8);
*flash_write_dest = first_short_value;
// Now for the rest of the function let's pretend this never happened.
++flash_write_dest;
++buffer;
--bytes_remaining;
}
// Handle body words
for (; bytes_remaining >= 2; bytes_remaining -= 2, buffer += 2) {
uint16_t buffer_word;
memcpy(&buffer_word, buffer, sizeof buffer_word);
*flash_write_dest++ = buffer_word;
}
// Handle trailing byte if present. This will be present if we started out
// aligned and we wrote an odd number of bytes or if we started out unaligned
// and wrote an even number of bytes.
if (bytes_remaining) {
// We need to write only a single byte, but we're only allowed to write
// words. If we write a single byte followed by 0xFFFF, we won't modify the
// second byte as bits are only allowed to be written from 1 -> 0. 1s will
// stay 1s, and 0s will stay 0s.
const uint16_t trailing_short_value = *buffer | 0xFF00;
*flash_write_dest = trailing_short_value;
}
// Buffer writing is complete, issue the buffer to flash command to actually
// commit the changes to memory.
prv_issue_command(sector_addr, S29VSCommand_BufferToFlash);
// Check the status register to make sure that the write has started.
status_t result = E_UNKNOWN;
const uint8_t sr = prv_read_status_register(sector_addr);
if ((sr & S29VSStatusBit_DeviceReady) == 0) {
// Program or erase operation in progress. Is it in the current bank?
result = ((sr & S29VSStatusBit_BankStatus) == 0)? S_SUCCESS : E_BUSY;
} else {
// Operation hasn't started. Something is wrong.
if (sr & S29VSStatusBit_SectorLockStatus) {
// Sector is write-protected.
result = E_INVALID_OPERATION;
} else if (sr & S29VSStatusBit_ProgramStatus) {
// Programming failed for some reason.
result = E_ERROR;
} else {
// The flash never appeared to go busy and there is no error. Either the
// flash write completed between the write command and the status register
// read (inopportune context switch or running in QEMU), or the write
// never started. It's possible to tell them apart by validating that the
// data was actually written to flash, but that adds even more complexity
// to this function. Let the upper layers verify that the write succeeded
// if they are concerned about reliability.
result = S_SUCCESS;
}
}
prv_allow_write_if_sector_is_not_protected(true, sector_addr);
flash_impl_release();
return FAILED(result) ? result : (int)bytes_in_page;
}
status_t flash_impl_get_write_status(void) {
flash_impl_use();
const uint8_t status = prv_read_status_register(0);
flash_impl_release();
if ((status & S29VSStatusBit_DeviceReady) == 0) return E_BUSY;
if ((status & S29VSStatusBit_ProgramSuspended) != 0) return E_AGAIN;
if ((status & S29VSStatusBit_ProgramStatus) != 0) return E_ERROR;
return S_SUCCESS;
}
uint8_t pbl_28517_flash_impl_get_status_register(uint32_t sector_addr) {
flash_impl_use();
const FlashAddress base_addr = flash_impl_get_sector_base_address(sector_addr);
const uint8_t status = prv_read_status_register(base_addr);
flash_impl_release();
return status;
}
status_t flash_impl_enter_low_power_mode(void) {
prv_flash_idle_gpios(false);
return S_SUCCESS;
}
status_t flash_impl_exit_low_power_mode(void) {
// it's ok to access s_num_flash_uses here directly, as only caller enter_stop_mode() is called
// only while interrupts are disabled
prv_flash_idle_gpios(s_num_flash_uses > 0);
return S_SUCCESS;
}
static void prv_switch_flash_mode(FMC_NORSRAMInitTypeDef *nor_init) {
FMC_NORSRAMCmd(FMC_Bank1_NORSRAM1, DISABLE);
FMC_NORSRAMInit(nor_init);
FMC_NORSRAMCmd(FMC_Bank1_NORSRAM1, ENABLE);
}
static uint16_t prv_get_num_wait_cycles(uint32_t flash_clock_freq) {
// wait_cycle table based on frequency (table 7.1)
// NOTE: 27MHZ frequency skipped due to data latency being 4 smaller than the wait_cycle
uint32_t wait_cycle[] = {
40000000 ,
54000000 ,
66000000 ,
80000000 ,
95000000 ,
104000000 ,
120000000
};
// find number wait states based on table
uint32_t wait_state;
for (wait_state = 4; wait_state < (ARRAY_LENGTH(wait_cycle) + 4); wait_state++) {
if (flash_clock_freq < wait_cycle[wait_state-4]) {
break;
}
}
return wait_state;
}
status_t flash_impl_set_burst_mode(bool burst_mode) {
const uint32_t MAX_FREQ = MHZ_TO_HZ(108); // max frequency of the flash 108MHZ
const uint32_t TAVDP_MIN = 60; // min addr setup time in tenths of ns
const uint32_t TADVO_MIN = 40; // min addr hold time in tenths
const uint32_t SETUP_STEP = MHZ_TO_HZ(16); // for data setup equation
const uint16_t WAIT_STATE_MASK = 0x7800; // mask for wait state binary for sync burst
flash_impl_use();
// get system clock tick speed
RCC_ClocksTypeDef clocks;
RCC_GetClocksFreq(&clocks);
uint32_t h_clock = clocks.HCLK_Frequency; // frequency in hertz
uint32_t time_per_cycle = ((uint64_t)(10000000000)) / h_clock; // period in 1/10th ns
FMC_NORSRAMTimingInitTypeDef nor_timing_init = {
// time between address write and address latch (AVD high)
// tAAVDS on datasheet, min 4 ns
//
// AVD low time
// tAVDP on datasheet, min 6 ns
.FMC_AddressSetupTime = (TAVDP_MIN / time_per_cycle) + 1, // give setup of min 6ns
// time between AVD high (address is available) and OE low (memory can write)
// tAVDO on the datasheet, min 4 ns
.FMC_AddressHoldTime = (TADVO_MIN / time_per_cycle) + 1, // gives hold of min 4ns
// time between OE low (memory can write) and valid data being available
// FIXME: optimize this equation
// current linear equation has slope of 1 cycle/SETUP_STEP, with initial value 1
// setupTime based on h_clock frequency
// equation derived from existing working values; 5 at 64Mhz, 8 at 128 Mhz
// the data was then interpolated into a line, with a padded value of 1
.FMC_DataSetupTime = (h_clock / SETUP_STEP) + 1,
// Time between chip selects
// not on the datasheet, picked a random safe number
// FIXME: at high bus frequencies, more than one cycle may be needed
.FMC_BusTurnAroundDuration = 1, // TODO: actually ok? See back-to-back Read/Write Cycle
.FMC_CLKDivision = 15, // Not used for async NOR
.FMC_DataLatency = 15, // Not used for async NOR
.FMC_AccessMode = FMC_AccessMode_A // Only used for ExtendedMode == FMC_ExtendedMode_Enable, which we don't use
};
FMC_NORSRAMInitTypeDef nor_init = {
.FMC_Bank = FMC_Bank1_NORSRAM1,
.FMC_DataAddressMux = FMC_DataAddressMux_Enable,
.FMC_MemoryType = FMC_MemoryType_NOR,
.FMC_MemoryDataWidth = FMC_NORSRAM_MemoryDataWidth_16b,
.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable,
.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable,
.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low,
.FMC_WrapMode = FMC_WrapMode_Disable,
.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState,
.FMC_WriteOperation = FMC_WriteOperation_Enable,
.FMC_WaitSignal = FMC_WaitSignal_Enable,
.FMC_ExtendedMode = FMC_ExtendedMode_Disable,
.FMC_WriteBurst = FMC_WriteBurst_Disable,
.FMC_ContinousClock = FMC_CClock_SyncOnly,
.FMC_ReadWriteTimingStruct = &nor_timing_init
};
// configure the peripheral before we try to read from it
prv_switch_flash_mode(&nor_init);
uint16_t configuration_register = prv_read_configuration_register();
// clear bits that are about to be set
configuration_register &= 0x0278; // clear bits [15:10], [8:7], [2:0]
// add one. This way, if (h_clock < MAX_FREQ), only divide by one (use h_clock as is)
// else divide by whatever is needed to be under MAX_FREQ
uint32_t clk_division = (h_clock / (MAX_FREQ + 1)) + 1;
// Update necessary parameters for synchronous modes
if (burst_mode) {
nor_init.FMC_BurstAccessMode = FMC_BurstAccessMode_Enable;
nor_init.FMC_WaitSignalActive = FMC_WaitSignalActive_DuringWaitState;
nor_timing_init.FMC_BusTurnAroundDuration = 1;
// nor_timing_init.FMC_DataSetupTime = 1; // FIXME: originally set to 1 for 64Mhz
// but sync burst was not working at this value;
// commented out so the DataSetupTime for ASYNC (up above) is used instead
// this is to ensure sync_burst works with dynamic changes to h_clk frequency
nor_timing_init.FMC_CLKDivision = clk_division; // divide h_clock if h_clock > 108MHZ
uint16_t wait_state = prv_get_num_wait_cycles(h_clock / clk_division);
// testing shows that a difference of 4 needs to be maintained between wait_state and latency
nor_timing_init.FMC_DataLatency = wait_state - 4;
// Set bits according to value needed - see Table 7.11 in data sheet
// [15] Device Read Mode 0b0 Synchronous Read Mode
// [14:11] Programmable Read Wait States 0bXXXX N wait cycles, wait states set to (N - 2)
// [10] RDY Polarity 0b1 RDY signal is active high (default)
// [8] RDY Timing 0b0 RDY active once cycle before data (default)
// [7] Output Drive Strength 0b0 Full Drive=Current Driver Strength (default)
// [2:0] Burst Length 0b000 Continuous (default)
configuration_register |= 0x400 | (((wait_state - 2) << 11) & (WAIT_STATE_MASK));
} else {
// Set bits according to value needed - see Table 7.11 in data sheet
// [15] Device Read Mode 0b1 Asynchronous Read Mode
// [14:11] Programmable Read Wait States 0b1011 13 wait cycles (default)
// [10] RDY Polarity 0b1 RDY signal is active high (default)
// [8] RDY Timing 0b1 RDY active with data (default)
// [7] Output Drive Strength 0b0 Full Drive=Current Driver Strength (default)
// [2:0] Burst Length 0b000 Continuous (default)
configuration_register |= 0xDD00;
}
prv_write_configuration_register(configuration_register);
prv_switch_flash_mode(&nor_init);
prv_poll_for_ready(0);
flash_impl_release();
return S_SUCCESS;
}
status_t flash_impl_blank_check_sector(FlashAddress addr) {
// FIXME: Blank check operation is only allowed in asynchronous mode. Fall
// back to a software blank check in synchronous mode.
const FlashAddress base_addr = flash_impl_get_sector_base_address(addr);
status_t ret = E_INTERNAL;
flash_impl_use();
uint8_t status = prv_read_status_register(base_addr);
if ((status & S29VSStatusBit_DeviceReady) == 0 ||
(status & (S29VSStatusBit_EraseSuspended |
S29VSStatusBit_ProgramSuspended)) != 0) {
ret = E_BUSY;
goto done;
}
prv_issue_command(base_addr, S29VSCommand_SectorBlank);
status = prv_poll_for_ready(base_addr);
ret = ((status & S29VSStatusBit_EraseStatus) == 0)? S_TRUE : S_FALSE;
done:
flash_impl_release();
return ret;
}
status_t flash_impl_blank_check_subsector(FlashAddress addr) {
return flash_impl_blank_check_sector(addr);
}
bool flash_check_whoami(void) {
uint16_t manufacturer_id = prv_read_manufacturer_id();
PBL_LOG(LOG_LEVEL_DEBUG, "Flash Manufacturer ID: 0x%"PRIx16, manufacturer_id);
return manufacturer_id == SPANSION_MANUFACTURER_ID ||
manufacturer_id == MACRONIX_MANUFACTURER_ID;
}
uint32_t flash_impl_get_typical_sector_erase_duration_ms(void) {
return 800;
}
uint32_t flash_impl_get_typical_subsector_erase_duration_ms(void) {
return 800;
}

View file

@ -0,0 +1,31 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
//! @file fpc_pinstrap.h
//!
//! This file implements an API to read the pinstrap values for an attached FPC (flexible printed
//! circuit). These values are used for version identification so we can figure out which version
//! of FPC is connected to our main PCB.
#define FPC_PINSTRAP_NOT_AVAILABLE 0xff
//! @return uint8_t a value between 0 and 8 to represent the pinstrap value. If the pinstrap
//! value isn't valid on this platform, FPC_PINSTRAP_NOT_AVAILABLE is returned.
uint8_t fpc_pinstrap_get_value(void);

View file

@ -0,0 +1,53 @@
/*
* 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/fpc_pinstrap.h"
#include "board/board.h"
#include "drivers/gpio.h"
static uint8_t prv_read_pinstrap_pin(InputConfig pin) {
// Read the pin value with it pulled up
gpio_input_init_pull_up_down(&pin, GPIO_PuPd_UP);
const bool pull_up_value = gpio_input_read(&pin);
// If the pull up was high, that either means it's actually high or floating. Read the
// pin again with a pull down to differentiate.
gpio_input_init_pull_up_down(&pin, GPIO_PuPd_DOWN);
const bool pull_down_value = gpio_input_read(&pin);
// Reset the pin to an analog input when we're not using it to reduce power draw.
gpio_analog_init(&pin);
if (pull_down_value != pull_up_value) {
// The value changed based on the pullup so it's floating.
return 2;
}
// It's not floating, return what the initial read told us.
return pull_up_value ? 1 : 0;
}
uint8_t fpc_pinstrap_get_value(void) {
// This is an uncommon operation so just configure the GPIOs as needed.
if (BOARD_CONFIG.fpc_pinstrap_1.gpio == GPIO_Port_NULL) {
return FPC_PINSTRAP_NOT_AVAILABLE;
}
return (prv_read_pinstrap_pin(BOARD_CONFIG.fpc_pinstrap_1) * 3)
+ prv_read_pinstrap_pin(BOARD_CONFIG.fpc_pinstrap_2);
}

90
src/fw/drivers/gpio.h Normal file
View file

@ -0,0 +1,90 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#include "board/board.h"
void gpio_use(GPIO_TypeDef* GPIOx);
void gpio_release(GPIO_TypeDef* GPIOx);
//! Initialize a GPIO as an output.
//!
//! @param pin_config the BOARD_CONFIG pin configuration struct
//! @param otype the output type of the pin (GPIO_OType_PP or GPIO_OType_OD)
//! @param speed the output slew rate
//! @note The slew rate should be set as low as possible for the
//! pin function to minimize ringing and RF interference.
void gpio_output_init(const OutputConfig *pin_config, GPIOOType_TypeDef otype,
GPIOSpeed_TypeDef speed);
//! Assert or deassert the output pin.
//!
//! Asserting the output drives the pin high if pin_config.active_high
//! is true, and drives it low if pin_config.active_high is false.
void gpio_output_set(const OutputConfig *pin_config, bool asserted);
//! Configure a GPIO alternate function.
//!
//! @param pin_config the BOARD_CONFIG pin configuration struct
//! @param otype the output type of the pin (GPIO_OType_PP or GPIO_OType_OD)
//! @param speed the output slew rate
//! @param pupd pull-up or pull-down configuration
//! @note The slew rate should be set as low as possible for the
//! pin function to minimize ringing and RF interference.
void gpio_af_init(const AfConfig *af_config, GPIOOType_TypeDef otype,
GPIOSpeed_TypeDef speed, GPIOPuPd_TypeDef pupd);
//! Configure a GPIO alternate function pin to minimize power consumption.
//!
//! Once a pin has been configured for low power, it is no longer
//! connected to its alternate function. \ref gpio_af_init will need to
//! be called again on the pin in order to configure it in alternate
//! function mode again.
void gpio_af_configure_low_power(const AfConfig *af_config);
//! Configure a GPIO alternate function pin to drive a constant output.
//!
//! Once a pin has been configured as a fixed output, it is no longer
//! connected to its alternate function. \ref gpio_af_init will need to
//! be called again on the pin in order to configure it in alternate
//! function mode again.
void gpio_af_configure_fixed_output(const AfConfig *af_config, bool asserted);
//! Configure all GPIOs in the system to optimize for power consumption.
//! At poweron most GPIOs can be configured as analog inputs instead of the
//! default digital input. This allows digital filtering logic to be shut down,
//! saving quite a bit of power.
void gpio_init_all(void);
//! Configure gpios as inputs (suitable for things like exti lines)
void gpio_input_init(const InputConfig *input_cfg);
//! Configure gpio as an input with internal pull up/pull down configured.
void gpio_input_init_pull_up_down(const InputConfig *input_cfg, GPIOPuPd_TypeDef pupd);
//! @return bool the current state of the GPIO pin
bool gpio_input_read(const InputConfig *input_cfg);
//! Configure gpios as analog inputs. Useful for unused GPIOs as this is their lowest power state.
void gpio_analog_init(const InputConfig *input_cfg);

33
src/fw/drivers/hrm.h Normal file
View file

@ -0,0 +1,33 @@
/*
* 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.
*/
#pragma once
#include "board/board.h"
#include <stdbool.h>
//! Initialize the HRM
void hrm_init(HRMDevice *dev);
//! Enable the HRM
void hrm_enable(HRMDevice *dev);
//! Disable the HRM
void hrm_disable(HRMDevice *dev);
//! Checks whether or not the HRM is enabled
bool hrm_is_enabled(HRMDevice *dev);

View file

@ -0,0 +1,50 @@
/*
* 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.
*/
#pragma once
#include "drivers/hrm.h"
#include "board/board.h"
#include "drivers/i2c_definitions.h"
#include "os/mutex.h"
#include "services/common/new_timer/new_timer.h"
#include "util/attributes.h"
#include <stdbool.h>
typedef enum HRMEnabledState {
HRMEnabledState_Uninitialized = 0,
HRMEnabledState_Disabled,
HRMEnabledState_PoweringOn,
HRMEnabledState_Enabled,
} HRMEnabledState;
typedef struct HRMDeviceState {
HRMEnabledState enabled_state;
PebbleMutex *lock;
TimerID timer;
uint32_t handshake_count;
} HRMDeviceState;
typedef const struct HRMDevice {
HRMDeviceState *state;
ExtiConfig handshake_int;
InputConfig int_gpio;
OutputConfig en_gpio;
I2CSlavePort *i2c_slave;
} HRMDevice;

603
src/fw/drivers/i2c.c Normal file
View file

@ -0,0 +1,603 @@
/*
* 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 "i2c.h"
#include "i2c_definitions.h"
#include "i2c_hal.h"
#include "board/board.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/rtc.h"
#include "FreeRTOS.h"
#include "kernel/pbl_malloc.h"
#include "os/tick.h"
#include "kernel/util/sleep.h"
#include "kernel/util/stop.h"
#include "os/mutex.h"
#include "semphr.h"
#include "services/common/analytics/analytics.h"
#include "system/logging.h"
#include "system/passert.h"
#include "util/size.h"
#if CAPABILITY_HAS_PMIC
#include "drivers/pmic.h"
#endif
#include <inttypes.h>
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#define I2C_ERROR_TIMEOUT_MS (1000)
#define I2C_TIMEOUT_ATTEMPTS_MAX (2 * 1000 * 1000)
// MFI NACKs while busy. We delay ~1ms between retries so this is approximately a 1000ms timeout.
// The longest operation of the MFi chip is "start signature generation", which seems to take
// 223-224 NACKs, but sometimes for unknown reasons it can take much longer.
#define I2C_NACK_COUNT_MAX (1000)
typedef enum {
Read,
Write
} TransferDirection;
typedef enum {
SendRegisterAddress, // Send a register address, followed by a repeat start for reads
NoRegisterAddress // Do not send a register address
} TransferType;
static uint32_t s_max_transfer_duration_ticks;
static void prv_analytics_track_i2c_error(void);
/*----------------SEMAPHORE/LOCKING FUNCTIONS--------------------------*/
static bool prv_semaphore_take(I2CBusState *bus) {
return (xSemaphoreTake(bus->event_semaphore, 0) == pdPASS);
}
static bool prv_semaphore_wait(I2CBusState *bus) {
TickType_t timeout_ticks = milliseconds_to_ticks(I2C_ERROR_TIMEOUT_MS);
return (xSemaphoreTake(bus->event_semaphore, timeout_ticks) == pdPASS);
}
static void prv_semaphore_give(I2CBusState *bus) {
// If this fails, something is very wrong
(void)xSemaphoreGive(bus->event_semaphore);
}
static portBASE_TYPE prv_semaphore_give_from_isr(I2CBusState *bus) {
portBASE_TYPE should_context_switch = pdFALSE;
(void)xSemaphoreGiveFromISR(bus->event_semaphore, &should_context_switch);
return should_context_switch;
}
/*-------------------BUS/PIN CONFIG FUNCTIONS--------------------------*/
// FIXME: These rail control functions should be moved to board-specific implementations
// https://pebbletechnology.atlassian.net/browse/PBL-32232
#if CAPABILITY_HAS_PMIC
void i2c_rail_ctl_pmic(I2CBus *bus, bool enable) {
set_ldo3_power_state(enable);
}
#endif
void i2c_rail_ctl_pin(I2CBus *bus, bool enable) {
gpio_output_set(&bus->rail_gpio, enable);
}
static void prv_rail_ctl(I2CBus *bus, bool enable) {
bus->rail_ctl_fn(bus, enable);
if (enable) {
// FIXME: The power tracking data is going to be bogus for any board with more than one bus
// with controllable power.
// https://pebbletechnology.atlassian.net/browse/PBL-32232 should address this
power_tracking_start(PowerSystem2v5Reg);
// 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.
psleep(20);
} else {
power_tracking_stop(PowerSystem2v5Reg);
}
}
//! Power down I2C bus power supply
//! Always lock bus and peripheral config access before use
static void prv_bus_rail_power_down(I2CBus *bus) {
if (!bus->rail_ctl_fn) {
return;
}
prv_rail_ctl(bus, false);
// Drain through pull-ups
OutputConfig out_scl = {
.gpio = bus->scl_gpio.gpio,
.gpio_pin = bus->scl_gpio.gpio_pin,
.active_high = true
};
gpio_output_init(&out_scl, GPIO_PuPd_NOPULL, GPIO_Speed_2MHz);
gpio_output_set(&out_scl, false);
OutputConfig out_sda = {
.gpio = bus->sda_gpio.gpio,
.gpio_pin = bus->sda_gpio.gpio_pin,
.active_high = true
};
gpio_output_init(&out_sda, GPIO_PuPd_NOPULL, GPIO_Speed_2MHz);
gpio_output_set(&out_sda, false);
bus->state->last_rail_stop_ticks = rtc_get_ticks();
}
//! Configure bus pins for use by I2C peripheral
//! Lock bus and peripheral config access before configuring pins
static void prv_bus_pins_cfg_i2c(I2CBus *bus) {
gpio_af_init(&bus->scl_gpio, GPIO_OType_OD, GPIO_Speed_50MHz, GPIO_PuPd_NOPULL);
gpio_af_init(&bus->sda_gpio, GPIO_OType_OD, GPIO_Speed_50MHz, GPIO_PuPd_NOPULL);
}
static void prv_bus_pins_cfg_input(I2CBus *bus) {
InputConfig in_scl = {
.gpio = bus->scl_gpio.gpio,
.gpio_pin = bus->scl_gpio.gpio_pin,
};
gpio_input_init(&in_scl);
InputConfig in_sda = {
.gpio = bus->sda_gpio.gpio,
.gpio_pin = bus->sda_gpio.gpio_pin,
};
gpio_input_init(&in_sda);
}
//! Power up I2C bus power supply
//! Always lock bus and peripheral config access before use
static void prv_bus_rail_power_up(I2CBus *bus) {
if (!bus->rail_ctl_fn) {
return;
}
static const uint32_t MIN_STOP_TIME_MS = 10;
// check that at least enough time has elapsed since the last turn-off
RtcTicks time_stopped_ms =
((rtc_get_ticks() - bus->state->last_rail_stop_ticks) * RTC_TICKS_HZ) / 1000;
I2C_DEBUG("Bus %s rail start after a delay of %"PRIu32"ms", bus->name,
(uint32_t)time_stopped_ms);
if (time_stopped_ms < MIN_STOP_TIME_MS) {
I2C_DEBUG("Waiting %"PRIu32"ms before enabling I2C bus %s rail.",
(uint32_t)(MIN_STOP_TIME_MS - time_stopped_ms), bus->name);
psleep(MIN_STOP_TIME_MS - time_stopped_ms);
}
prv_bus_pins_cfg_input(bus);
prv_rail_ctl(bus, true);
}
//! 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 prv_bus_enable(I2CBus *bus) {
// Don't power up rail if the bus is already in use (enable can be called to reset bus)
if (bus->state->user_count == 0) {
prv_bus_rail_power_up(bus);
}
prv_bus_pins_cfg_i2c(bus);
i2c_hal_enable(bus);
}
//! 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 prv_bus_disable(I2CBus *bus) {
i2c_hal_disable(bus);
// Do not de-power rail if there are still devices using bus (just reset peripheral and pin
// configuration during a bus reset)
if (bus->state->user_count == 0) {
prv_bus_rail_power_down(bus);
} else {
prv_bus_pins_cfg_input(bus);
}
}
//! Perform a soft reset of the bus
//! Always lock the bus before reset
static void prv_bus_reset(I2CBus *bus) {
prv_bus_disable(bus);
prv_bus_enable(bus);
}
/*---------------INIT/USE/RELEASE/RESET FUNCTIONS----------------------*/
void i2c_init(I2CBus *bus) {
PBL_ASSERTN(bus);
*bus->state = (I2CBusState) {
.event_semaphore = xSemaphoreCreateBinary(),
.bus_mutex = mutex_create(),
};
// Must give token before one can be taken without blocking
xSemaphoreGive(bus->state->event_semaphore);
i2c_hal_init(bus);
if (bus->rail_gpio.gpio) {
gpio_output_init(&bus->rail_gpio, GPIO_OType_PP, GPIO_Speed_2MHz);
}
prv_bus_rail_power_down(bus);
}
void i2c_use(I2CSlavePort *slave) {
PBL_ASSERTN(slave);
mutex_lock(slave->bus->state->bus_mutex);
if (slave->bus->state->user_count == 0) {
prv_bus_enable(slave->bus);
}
slave->bus->state->user_count++;
mutex_unlock(slave->bus->state->bus_mutex);
}
void i2c_release(I2CSlavePort *slave) {
PBL_ASSERTN(slave);
mutex_lock(slave->bus->state->bus_mutex);
if (slave->bus->state->user_count == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "Attempted release of disabled bus %s", slave->bus->name);
mutex_unlock(slave->bus->state->bus_mutex);
return;
}
slave->bus->state->user_count--;
if (slave->bus->state->user_count == 0) {
prv_bus_disable(slave->bus);
}
mutex_unlock(slave->bus->state->bus_mutex);
}
void i2c_reset(I2CSlavePort *slave) {
PBL_ASSERTN(slave);
// Take control of bus; only one task may use bus at a time
mutex_lock(slave->bus->state->bus_mutex);
if (slave->bus->state->user_count == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "Attempted reset of disabled bus %s when still in use by "
"another bus", slave->bus->name);
mutex_unlock(slave->bus->state->bus_mutex);
return;
}
PBL_LOG(LOG_LEVEL_WARNING, "Resetting I2C bus %s", slave->bus->name);
// decrement user count for reset so that if this user is the only user, the
// bus will be powered down during the reset
slave->bus->state->user_count--;
// Reset and reconfigure bus and pins
prv_bus_reset(slave->bus);
// Restore user count
slave->bus->state->user_count++;
mutex_unlock(slave->bus->state->bus_mutex);
}
bool i2c_bitbang_recovery(I2CSlavePort *slave) {
PBL_ASSERTN(slave);
static const int MAX_TOGGLE_COUNT = 10;
static const int TOGGLE_DELAY = 10;
// Protect access to bus
mutex_lock(slave->bus->state->bus_mutex);
if (slave->bus->state->user_count == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "Attempted bitbang recovery on disabled bus %s", slave->bus->name);
mutex_unlock(slave->bus->state->bus_mutex);
return false;
}
InputConfig in_sda = {
.gpio = slave->bus->sda_gpio.gpio,
.gpio_pin = slave->bus->sda_gpio.gpio_pin,
};
gpio_input_init(&in_sda);
OutputConfig out_scl = {
.gpio = slave->bus->scl_gpio.gpio,
.gpio_pin = slave->bus->scl_gpio.gpio_pin,
.active_high = true
};
gpio_output_init(&out_scl, GPIO_PuPd_NOPULL, GPIO_Speed_2MHz);
gpio_output_set(&out_scl, true);
bool recovered = false;
for (int i = 0; i < MAX_TOGGLE_COUNT; ++i) {
gpio_output_set(&out_scl, false);
psleep(TOGGLE_DELAY);
gpio_output_set(&out_scl, true);
psleep(TOGGLE_DELAY);
if (gpio_input_read(&in_sda)) {
recovered = true;
break;
}
}
if (recovered) {
PBL_LOG(LOG_LEVEL_DEBUG, "I2C Bus %s recovered", slave->bus->name);
} else {
PBL_LOG(LOG_LEVEL_ERROR, "I2C Bus %s still hung after bitbang reset", slave->bus->name);
}
prv_bus_pins_cfg_i2c(slave->bus);
prv_bus_reset(slave->bus);
mutex_unlock(slave->bus->state->bus_mutex);
return recovered;
}
/*--------------------DATA TRANSFER FUNCTIONS--------------------------*/
//! Wait a short amount of time for busy bit to clear
static bool prv_wait_for_not_busy(I2CBus *bus) {
static const int WAIT_DELAY = 10; // milliseconds
if (i2c_hal_is_busy(bus)) {
psleep(WAIT_DELAY);
if (i2c_hal_is_busy(bus)) {
PBL_LOG(LOG_LEVEL_ERROR, "Timed out waiting for bus %s to become non-busy", bus->name);
return false;
}
}
return true;
}
//! Set up and start a transfer to a bus, wait for it to finish and clean up after the transfer
//! has completed
static bool prv_do_transfer(I2CBus *bus, TransferDirection direction, uint16_t device_address,
uint8_t register_address, uint32_t size, uint8_t *data,
TransferType type) {
// Take control of bus; only one task may use bus at a time
mutex_lock(bus->state->bus_mutex);
if (bus->state->user_count == 0) {
PBL_LOG(LOG_LEVEL_ERROR, "Attempted access to disabled bus %s", bus->name);
mutex_unlock(bus->state->bus_mutex);
return false;
}
// Disable stop mode while the I2C transfer is in progress - stop mode disables I2C peripheral
stop_mode_disable(bus->stop_mode_inhibitor);
// 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 (i2c_hal_is_busy(bus)) {
prv_bus_reset(bus);
if (!prv_wait_for_not_busy(bus)) {
// Bus did not recover after reset
stop_mode_enable(bus->stop_mode_inhibitor);
mutex_unlock(bus->state->bus_mutex);
PBL_LOG(LOG_LEVEL_ERROR, "I2C bus did not recover after reset (%s)", bus->name);
prv_analytics_track_i2c_error();
return false;
}
}
// Take binary semaphore so that next take will block
PBL_ASSERT(prv_semaphore_take(bus->state), "Could not acquire semaphore token");
// Set up transfer
bus->state->transfer = (I2CTransfer) {
.device_address = device_address,
.register_address = register_address,
.direction = direction,
.type = type,
.size = size,
.idx = 0,
.data = data,
};
i2c_hal_init_transfer(bus);
bus->state->transfer_nack_count = 0;
bus->state->transfer_start_ticks = rtc_get_ticks();
bool result = false;
bool complete = false;
do {
i2c_hal_start_transfer(bus);
// Wait on semaphore until it is released by interrupt or a timeout occurs
if (prv_semaphore_wait(bus->state)) {
if ((bus->state->transfer_event == I2CTransferEvent_TransferComplete) ||
(bus->state->transfer_event == I2CTransferEvent_Error)) {
// Track the max transfer duration so we can keep tabs on the MFi chip's nacking behavior
const uint32_t duration_ticks = rtc_get_ticks() - bus->state->transfer_start_ticks;
if (duration_ticks > s_max_transfer_duration_ticks) {
s_max_transfer_duration_ticks = duration_ticks;
}
if (bus->state->transfer_event == I2CTransferEvent_Error) {
PBL_LOG(LOG_LEVEL_ERROR, "I2C Error on bus %s", bus->name);
}
complete = true;
result = (bus->state->transfer_event == I2CTransferEvent_TransferComplete);
} else if (bus->state->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->state->transfer_nack_count++;
// Wait 1-2ms:
psleep(2);
} else {
// Too many NACKs received, abort transfer
i2c_hal_abort_transfer(bus);
complete = true;
PBL_LOG(LOG_LEVEL_ERROR, "I2C Error: too many NACKs received on bus %s", bus->name);
break;
}
} else {
// Timeout, abort transfer
i2c_hal_abort_transfer(bus);
complete = true;
PBL_LOG(LOG_LEVEL_ERROR, "Transfer timed out on bus %s", bus->name);
break;
}
} while (!complete);
// Return semaphore token so another transfer can be started
prv_semaphore_give(bus->state);
// 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 (!prv_wait_for_not_busy(bus)) {
// Reset I2C bus if busy flag does not clear
prv_bus_reset(bus);
}
stop_mode_enable(bus->stop_mode_inhibitor);
mutex_unlock(bus->state->bus_mutex);
if (!result) {
prv_analytics_track_i2c_error();
}
return result;
}
bool i2c_read_register(I2CSlavePort *slave, uint8_t register_address, uint8_t *result) {
return i2c_read_register_block(slave, register_address, 1, result);
}
bool i2c_read_register_block(I2CSlavePort *slave, uint8_t register_address_start,
uint32_t read_size, uint8_t* result_buffer) {
PBL_ASSERTN(slave);
PBL_ASSERTN(result_buffer);
// Do transfer locks the bus
bool result = prv_do_transfer(slave->bus, Read, slave->address, register_address_start, read_size,
result_buffer, SendRegisterAddress);
if (!result) {
PBL_LOG(LOG_LEVEL_ERROR, "Read failed on bus %s", slave->bus->name);
}
return result;
}
bool i2c_read_block(I2CSlavePort *slave, uint32_t read_size, uint8_t* result_buffer) {
PBL_ASSERTN(slave);
PBL_ASSERTN(result_buffer);
bool result = prv_do_transfer(slave->bus, Read, slave->address, 0, read_size, result_buffer,
NoRegisterAddress);
if (!result) {
PBL_LOG(LOG_LEVEL_ERROR, "Block read failed on bus %s", slave->bus->name);
}
return result;
}
bool i2c_write_register(I2CSlavePort *slave, uint8_t register_address, uint8_t value) {
return i2c_write_register_block(slave, register_address, 1, &value);
}
bool i2c_write_register_block(I2CSlavePort *slave, uint8_t register_address_start,
uint32_t write_size, const uint8_t* buffer) {
PBL_ASSERTN(slave);
PBL_ASSERTN(buffer);
// Do transfer locks the bus
bool result = prv_do_transfer(slave->bus, Write, slave->address, register_address_start,
write_size, (uint8_t*)buffer, SendRegisterAddress);
if (!result) {
PBL_LOG(LOG_LEVEL_ERROR, "Write failed on bus %s", slave->bus->name);
}
return result;
}
bool i2c_write_block(I2CSlavePort *slave, uint32_t write_size, const uint8_t* buffer) {
PBL_ASSERTN(slave);
PBL_ASSERTN(buffer);
// Do transfer locks the bus
bool result = prv_do_transfer(slave->bus, Write, slave->address, 0, write_size, (uint8_t*)buffer,
NoRegisterAddress);
if (!result) {
PBL_LOG(LOG_LEVEL_ERROR, "Block write failed on bus %s", slave->bus->name);
}
return result;
}
/*----------------------HAL INTERFACE--------------------------------*/
portBASE_TYPE i2c_handle_transfer_event(I2CBus *bus, I2CTransferEvent event) {
bus->state->transfer_event = event;
return prv_semaphore_give_from_isr(bus->state);
}
/*------------------------ANALYTICS----------------------------------*/
static void prv_analytics_track_i2c_error(void) {
analytics_inc(ANALYTICS_DEVICE_METRIC_I2C_ERROR_COUNT, AnalyticsClient_System);
}
void analytics_external_collect_i2c_stats(void) {
analytics_set(ANALYTICS_DEVICE_METRIC_I2C_MAX_TRANSFER_DURATION_TICKS,
s_max_transfer_duration_ticks, AnalyticsClient_System);
s_max_transfer_duration_ticks = 0;
}
/*------------------------COMMAND FUNCTIONS--------------------------*/
// FIXME: Move to board-specific implementations
// https://pebbletechnology.atlassian.net/browse/PBL-32232
#if PLATFORM_TINTIN
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)) {
prv_bus_rail_power_up(I2C_MFI->bus);
} else {
prv_bus_rail_power_down(I2C_MFI->bus);
}
}
#endif

97
src/fw/drivers/i2c.h Normal file
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.
*/
#pragma once
#include "board/board.h"
#include <stdbool.h>
#include <stdint.h>
//! Start using the I2C bus to which \a slave is connected
//! Must be called before any other reads or writes to the slave are performed
//! @param slave I2C slave reference, which will identify the bus to use
void i2c_use(I2CSlavePort *slave);
//! Stop using the I2C bus to which \a slave is connected
//! Call when done communicating with the slave
//! @param slave I2C slave reference, which will identify the bus to release
void i2c_release(I2CSlavePort *slave);
//! Reset the slave
//! Will cycle the power to and re-initialize the bus to which \a slave is connected, if this is
//! supported for the bus.
//! @param slave I2C slave reference, which will identify the bus to be reset
void i2c_reset(I2CSlavePort *slave);
//! Manually bang out the clock on the bus to which \a slave is connected until the data line
//! recovers for a period or we timeout waiting for it to recover
//! Must not be called before \ref i2c_use has been called for the slave
//! @param slave I2C slave reference, which will identify the bus to be recovered
//! @return true if the data line recovered, false otherwise
bool i2c_bitbang_recovery(I2CSlavePort *slave);
//! Read the value of a register
//! Must not be called before \ref i2c_use has been called for the slave
//! @param slave I2C slave to communicate with
//! @param register_address Address of register to read
//! @param result Pointer to destination buffer
//! @return true if transfer succeeded, false if error occurred
bool i2c_read_register(I2CSlavePort *slave, uint8_t register_address, uint8_t *result);
//! Read a sequence of registers starting from \a register_address_start
//! Must not be called before \ref i2c_use has been called for the slave
//! @param slave I2C slave to communicate with
//! @param register_address_start Address of first register to read
//! @param read_size Number of bytes to read
//! @param result_buffer Pointer to destination buffer
//! @return true if transfer succeeded, false if error occurred
bool i2c_read_register_block(I2CSlavePort *slave, uint8_t register_address_start,
uint32_t read_size, uint8_t* result_buffer);
//! Read a block of data without sending a register address before doing so.
//! Must not be called before \ref i2c_use has been called for the slave
//! @param slave I2C slave to communicate with
//! @param read_size Number of bytes to read
//! @param result_buffer Pointer to destination buffer
//! @return true if transfer succeeded, false if error occurred
bool i2c_read_block(I2CSlavePort *slave, uint32_t read_size, uint8_t* result_buffer);
//! Write to a register
//! Must not be called before \ref i2c_use has been called for the slave
//! @param slave I2C slave to communicate with
//! @param register_address Address of register to write to
//! @param value Data value to write
//! @return true if transfer succeeded, false if error occurred
bool i2c_write_register(I2CSlavePort *slave, uint8_t register_address, uint8_t value);
//! Write to a sequence of registers starting from \a register_address_start
//! Must not be called before \ref i2c_use has been called for the slave
//! @param slave I2C slave to communicate with
//! @param register_address_start Address of first register to read
//! @param write_size Number of bytes to write
//! @param buffer Pointer to source buffer
//! @return true if transfer succeeded, false if error occurred
bool i2c_write_register_block(I2CSlavePort *slave, uint8_t register_address_start,
uint32_t write_size, const uint8_t* buffer);
//! Write a block of data without sending a register address before doing so.
//! Must not be called before \ref i2c_use has been called for the slave
//! @param slave I2C slave to communicate with
//! @param write_size Number of bytes to write
//! @param buffer Pointer to source buffer
//! @return true if transfer succeeded, false if error occurred
bool i2c_write_block(I2CSlavePort *slave, uint32_t write_size, const uint8_t* buffer);

View file

@ -0,0 +1,105 @@
/*
* 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.
*/
#pragma once
#include "os/mutex.h"
#include "kernel/util/stop.h"
#include "freertos_types.h"
#include "portmacro.h"
#include <stdbool.h>
#include <stdint.h>
typedef enum I2CTransferEvent {
I2CTransferEvent_Timeout,
I2CTransferEvent_TransferComplete,
I2CTransferEvent_NackReceived,
I2CTransferEvent_Error,
} I2CTransferEvent;
typedef enum {
I2CTransferDirection_Read,
I2CTransferDirection_Write
} I2CTransferDirection;
typedef enum {
// Send a register address, followed by a repeat start for reads
I2CTransferType_SendRegisterAddress,
// Do not send a register address; used for block writes/reads
I2CTransferType_NoRegisterAddress
} I2CTransferType;
typedef enum I2CTransferState {
I2CTransferState_WriteAddressTx,
I2CTransferState_WriteRegAddress,
I2CTransferState_RepeatStart,
I2CTransferState_WriteAddressRx,
I2CTransferState_WaitForData,
I2CTransferState_ReadData,
I2CTransferState_WriteData,
I2CTransferState_EndWrite,
I2CTransferState_Complete,
} I2CTransferState;
typedef struct I2CTransfer {
I2CTransferState state;
uint16_t device_address;
I2CTransferDirection direction;
I2CTransferType type;
uint8_t register_address;
uint32_t size;
uint32_t idx;
uint8_t *data;
} I2CTransfer;
typedef struct I2CBusState {
I2CTransfer transfer;
I2CTransferEvent transfer_event;
int transfer_nack_count;
RtcTicks transfer_start_ticks;
int user_count;
RtcTicks last_rail_stop_ticks;
SemaphoreHandle_t event_semaphore;
PebbleMutex *bus_mutex;
} I2CBusState;
struct I2CBus {
I2CBusState *const state;
const struct I2CBusHal *const hal;
AfConfig scl_gpio; ///< Alternate Function configuration for SCL pin
AfConfig sda_gpio; ///< Alternate Function configuration for SDA pin
OutputConfig rail_gpio; ///< Control pin for rail
void (* const rail_ctl_fn)(I2CBus *device, bool enabled); ///< Control function for this rail.
StopModeInhibitor stop_mode_inhibitor;
const char *name; //! Device ID for logging purposes
};
struct I2CSlavePort {
const I2CBus *bus;
uint16_t address;
};
//! Initialize the I2C driver.
void i2c_init(I2CBus *bus);
//! Transfer event handler implemented in i2c.c and called by HAL implementation
portBASE_TYPE i2c_handle_transfer_event(I2CBus *device, I2CTransferEvent event);
#define I2C_DEBUG(fmt, args...) \
PBL_LOG_COLOR_D(LOG_DOMAIN_I2C, LOG_LEVEL_DEBUG, LOG_COLOR_LIGHT_MAGENTA, fmt, ## args)

35
src/fw/drivers/i2c_hal.h Normal file
View file

@ -0,0 +1,35 @@
/*
* 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.
*/
#pragma once
#include "board/board.h"
#include <stdbool.h>
void i2c_hal_init(I2CBus *bus);
void i2c_hal_enable(I2CBus *bus);
void i2c_hal_disable(I2CBus *bus);
bool i2c_hal_is_busy(I2CBus *bus);
void i2c_hal_abort_transfer(I2CBus *bus);
void i2c_hal_init_transfer(I2CBus *bus);
void i2c_hal_start_transfer(I2CBus *bus);

30
src/fw/drivers/imu.h Normal file
View file

@ -0,0 +1,30 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
void imu_init(void);
//! Put all IMU devices into normal mode
void imu_power_up(void);
//! Put all IMU devices into low-power mode
void imu_power_down(void);
bool imu_self_test(void);
bool imu_sanity_check(void);

View file

@ -0,0 +1,898 @@
/*
* 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 "bma255.h"
#include "bma255_regs.h"
#include "bma255_private.h"
#include "console/prompt.h"
#include "drivers/accel.h"
#include "drivers/exti.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/rtc.h"
#include "drivers/spi.h"
#include "kernel/util/delay.h"
#include "kernel/util/sleep.h"
#include "system/logging.h"
#include "system/passert.h"
#include "util/math.h"
#include "util/units.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#include <mcu.h>
#define BMA255_DEBUG 0
#if BMA255_DEBUG
#define BMA255_DBG(msg, ...) \
do { \
PBL_LOG(LOG_LEVEL_DEBUG, msg, __VA_ARGS__); \
} while (0);
#else
#define BMA255_DBG(msg, ...)
#endif
#define SELFTEST_SIGN_POSITIVE (0x1 << 2)
#define SELFTEST_SIGN_NEGATIVE (0x0)
// The BMA255 is capable of storing up to 32 frames.
// Conceptually each frame consists of three 16-bit words corresponding to the x, y and z- axis.
#define BMA255_FIFO_MAX_FRAMES (32)
#define BMA255_FIFO_FRAME_SIZE_BYTES (3 * 2)
#define BMA255_FIFO_SIZE_BYTES (BMA255_FIFO_MAX_FRAMES * BMA255_FIFO_FRAME_SIZE_BYTES)
// Driver state
static BMA255PowerMode s_accel_power_mode = BMA255PowerMode_Normal;
static bool s_fifo_is_enabled = false;
static bool s_shake_detection_enabled = false;
static bool s_accel_outstanding_motion_work = false;
static bool s_accel_outstanding_data_work = false;
static bool s_fifo_overrun_detected = false;
// Forward declarations
static void prv_configure_operating_mode(void);
static void prv_bma255_IRQ1_handler(bool *should_context_switch);
static void prv_bma255_IRQ2_handler(bool *should_context_switch);
static void prv_set_accel_power_mode(BMA255PowerMode mode);
// The BMA255 reports each G in powers of 2 with full deflection at +-2^11
// So scale all readings by (scale)/(2^11) to get G
// And scale the result by 1000 to allow for easier interger math
typedef enum {
BMA255Scale_2G = 980, // 2000/2048
BMA255Scale_4G = 1953, // 4000/2048
BMA255Scale_8G = 3906, // 8000/2048
BMA255Scale_16G = 7813, // 16000/2048
} BMA255Scale;
static int16_t s_raw_unit_to_mgs = BMA255Scale_2G;
typedef enum {
AccelOperatingMode_Data,
AccelOperatingMode_ShakeDetection,
AccelOperatingMode_DoubleTapDetection,
AccelOperatingModeCount,
} AccelOperatingMode;
static struct {
bool enabled;
bool using_interrupts;
BMA255ODR odr;
} s_operating_states[AccelOperatingModeCount] = {
[AccelOperatingMode_Data] = {
.enabled = false,
.using_interrupts = false,
.odr = BMA255ODR_125HZ,
},
[AccelOperatingMode_ShakeDetection] = {
.enabled = false,
.using_interrupts = false,
.odr = BMA255ODR_125HZ,
},
[AccelOperatingMode_DoubleTapDetection] = {
.enabled = false,
.using_interrupts = false,
.odr = BMA255ODR_125HZ,
},
};
void bma255_init(void) {
bma255_gpio_init();
if (!bma255_query_whoami()) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to query BMA255");
return;
}
const bool pass = bma255_selftest();
if (pass) {
PBL_LOG(LOG_LEVEL_DEBUG, "BMA255 self test pass, all 3 axis");
} else {
PBL_LOG(LOG_LEVEL_ERROR, "BMA255 self test failed one or more axis");
}
// Workaround to fix FIFO Frame Leakage: Disable temperature sensor (we're not using it anyways)
// See Section 2.2.1 of https://drive.google.com/a/pebble.com/file/d/0B9tTN3OlYns3bEZaczdoZUU3UEk/view
bma255_write_register(BMA255Register_EXTENDED_MEMORY_MAP, BMA255_EXTENDED_MEMORY_MAP_OPEN);
bma255_write_register(BMA255Register_EXTENDED_MEMORY_MAP, BMA255_EXTENDED_MEMORY_MAP_OPEN);
bma255_write_register(BMA255Register_TEMPERATURE_SENSOR_CTRL, BMA255_TEMPERATURE_SENSOR_DISABLE);
bma255_write_register(BMA255Register_EXTENDED_MEMORY_MAP, BMA255_EXTENDED_MEMORY_MAP_CLOSE);
exti_configure_pin(BOARD_CONFIG_ACCEL.accel_ints[0], ExtiTrigger_Rising, prv_bma255_IRQ1_handler);
exti_configure_pin(BOARD_CONFIG_ACCEL.accel_ints[1], ExtiTrigger_Rising, prv_bma255_IRQ2_handler);
}
bool bma255_query_whoami(void) {
const uint8_t chip_id = bma255_read_register(BMA255Register_BGW_CHIP_ID);
PBL_LOG(LOG_LEVEL_DEBUG, "Read BMA255 whoami byte 0x%"PRIx8", expecting 0x%"PRIx8,
chip_id, BMA255_CHIP_ID);
return (chip_id == BMA255_CHIP_ID);
}
static uint64_t prv_get_curr_system_time_ms(void) {
time_t time_s;
uint16_t time_ms;
rtc_get_time_ms(&time_s, &time_ms);
return (((uint64_t)time_s) * 1000 + time_ms);
}
void bma255_set_scale(BMA255Scale scale) {
uint8_t value = 0;
switch (scale) {
case BMA255Scale_2G:
value = 0x3;
break;
case BMA255Scale_4G:
value = 0x5;
break;
case BMA255Scale_8G:
value = 0x8;
break;
case BMA255Scale_16G:
value = 0xc;
break;
default:
WTF;
}
bma255_write_register(BMA255Register_PMU_RANGE, value);
s_raw_unit_to_mgs = scale;
}
static int16_t prv_raw_to_mgs(int16_t raw_val) {
int16_t mgs = ((int32_t)raw_val * s_raw_unit_to_mgs) / 1000;
return mgs;
}
static int16_t prv_conv_raw_to_12bit(const uint8_t registers[2]) {
int16_t reading = ((registers[0] >> 4) & 0x0F) | ((int16_t)registers[1] << 4);
if (reading & 0x0800) {
reading |= 0xF000;
}
return reading;
}
static void prv_convert_accel_raw_data_to_mgs(const uint8_t *buf, AccelDriverSample *data) {
int16_t readings[3];
for (int i = 0; i < 3; ++i) {
readings[i] = prv_conv_raw_to_12bit(&buf[i*2]);
}
const AccelConfig *cfg = &BOARD_CONFIG_ACCEL.accel_config;
*data = (AccelDriverSample) {
.x = (cfg->axes_inverts[AXIS_X] ? -1 : 1) *
prv_raw_to_mgs(readings[cfg->axes_offsets[AXIS_X]]),
.y = (cfg->axes_inverts[AXIS_Y] ? -1 : 1) *
prv_raw_to_mgs(readings[cfg->axes_offsets[AXIS_Y]]),
.z = (cfg->axes_inverts[AXIS_Z] ? -1 : 1) *
prv_raw_to_mgs(readings[cfg->axes_offsets[AXIS_Z]]),
};
}
static void prv_read_curr_accel_data(AccelDriverSample *data) {
uint8_t raw_buf[BMA255_FIFO_FRAME_SIZE_BYTES];
bma255_burst_read(BMA255Register_ACCD_X_LSB, raw_buf, sizeof(raw_buf));
prv_convert_accel_raw_data_to_mgs(raw_buf, data);
// FIXME: assuming the timestamp on the samples is NOW! PBL-33765
data->timestamp_us = prv_get_curr_system_time_ms() * 1000;
BMA255_DBG("%"PRId16" %"PRId16" %"PRId16, data->x, data->y, data->z);
}
typedef enum {
BMA255Axis_X = 0,
BMA255Axis_Y,
BMA255Axis_Z,
} BMA255Axis;
static void prv_drain_fifo(void) {
// TODO: I think the ideal thing to do here would be to invoke the accel_cb_new_sample() while
// the SPI transaction is in progress so we don't need a static ~500 byte buffer. (This is what
// we do in the bmi160 driver) However, since we are oversampling super aggressively with the
// bma255, I'm concerned about changing the timing of how fast we drain things. Thus, just use a
// static buffer for now. This should be safe because only one thread should be draining the data.
static AccelDriverSample data[BMA255_FIFO_MAX_FRAMES];
const uint64_t timestamp_us = prv_get_curr_system_time_ms() * 1000;
const uint32_t sampling_interval_us = accel_get_sampling_interval();
uint8_t fifo_status = bma255_read_register(BMA255Register_FIFO_STATUS);
BMA255_DBG("Drain %"PRIu8" samples", num_samples_available);
const uint8_t num_samples_available = fifo_status & 0x3f;
if (num_samples_available == 0) {
return;
}
bma255_prepare_txn(BMA255Register_FIFO_DATA | BMA255_READ_FLAG);
for (int i = 0; i < num_samples_available; ++i) {
uint8_t buf[BMA255_FIFO_FRAME_SIZE_BYTES];
for (int j = 0; j < BMA255_FIFO_FRAME_SIZE_BYTES; ++j) {
buf[j] = bma255_send_and_receive_byte(0);
}
prv_convert_accel_raw_data_to_mgs(buf, &data[i]);
}
bma255_end_txn();
// Timestamp & Dispatch data
for (int i = 0; i < num_samples_available; ++i) {
// Make a timestamp approximation based on the current time, the sample
// being processed and the sampling interval.
data[i].timestamp_us = timestamp_us - ((num_samples_available - i) * sampling_interval_us);
BMA255_DBG("%2d: %"PRId16" %"PRId16" %"PRId16" %"PRIu32,
i, data[i].x, data[i].y, data[i].z, (uint32_t)data[i].timestamp_us);
accel_cb_new_sample(&data[i]);
}
// clear of fifo overrun flag must happen after draining samples, also the samples available will
// get drained too!
if ((fifo_status & 0x80) && !s_fifo_overrun_detected) {
s_fifo_overrun_detected = true;
// We don't clear the interrupt here because you are only supposed to touch the fifo config
// registers while in standby mode.
PBL_LOG(LOG_LEVEL_WARNING, "bma255 fifo overrun detected: 0x%x!", fifo_status);
}
}
static void prv_handle_data(void) {
s_accel_outstanding_data_work = false;
if (s_fifo_is_enabled) {
prv_drain_fifo();
return;
}
AccelDriverSample data;
prv_read_curr_accel_data(&data);
accel_cb_new_sample(&data);
}
static void prv_handle_motion_interrupts(void) {
s_accel_outstanding_motion_work = false;
const uint8_t int0_status = bma255_read_register(BMA255Register_INT_STATUS_0);
const uint8_t int2_status = bma255_read_register(BMA255Register_INT_STATUS_2);
bool anymotion = (int0_status & BMA255_INT_STATUS_0_SLOPE_MASK);
if (anymotion) {
const AccelConfig *cfg = &BOARD_CONFIG_ACCEL.accel_config;
IMUCoordinateAxis axis = AXIS_X;
bool invert = false;
if (int2_status & BMA255_INT_STATUS_2_SLOPE_FIRST_X) {
axis = AXIS_X;
invert = cfg->axes_inverts[AXIS_X];
} else if (int2_status & BMA255_INT_STATUS_2_SLOPE_FIRST_Y) {
axis = AXIS_Y;
invert = cfg->axes_inverts[AXIS_Y];
} else if (int2_status & BMA255_INT_STATUS_2_SLOPE_FIRST_Z) {
axis = AXIS_Z;
invert = cfg->axes_inverts[AXIS_Z];
} else {
BMA255_DBG("No Axis?: 0x%"PRIx8" 0x%"PRIx8, int0_status, int2_status);
}
int32_t direction = ((int2_status & BMA255_INT_STATUS_2_SLOPE_SIGN) == 0) ? 1 : -1;
direction *= (invert ? -1 : 1);
accel_cb_shake_detected(axis, direction);
}
}
// Services tap/motion interrupts
static void prv_bma255_IRQ1_handler(bool *should_context_switch) {
BMA255_DBG("Slope Int");
if (!s_accel_outstanding_motion_work) {
s_accel_outstanding_motion_work = true;
accel_offload_work_from_isr(prv_handle_motion_interrupts, should_context_switch);
}
}
// Services data / fifo interrupts.
// NOTE: The BMA255 Errata specifically states that we should keep the fifo /
// data interrupt on INT2 to avoid "data inconsistencies" which arise when
// we have it fifo / data interrupt on INT1.
static void prv_bma255_IRQ2_handler(bool *should_context_switch) {
BMA255_DBG("Data Int");
if (!s_accel_outstanding_data_work) {
s_accel_outstanding_data_work = true;
accel_offload_work_from_isr(prv_handle_data, should_context_switch);
}
}
static void prv_update_accel_interrupts(bool enable, AccelOperatingMode mode) {
s_operating_states[mode].using_interrupts = enable;
bool enable_interrupts = false;
for (uint32_t i = 0; i < ARRAY_LENGTH(s_operating_states); i++) {
if (s_operating_states[i].using_interrupts) {
enable_interrupts = true;
break;
}
}
if (enable_interrupts) {
exti_enable(BOARD_CONFIG_ACCEL.accel_ints[0]);
exti_enable(BOARD_CONFIG_ACCEL.accel_ints[1]);
} else {
exti_disable(BOARD_CONFIG_ACCEL.accel_ints[0]);
exti_disable(BOARD_CONFIG_ACCEL.accel_ints[1]);
}
}
uint32_t accel_get_sampling_interval(void) {
BMA255ODR odr_max = 0;
for (uint32_t i = 0; i < ARRAY_LENGTH(s_operating_states); i++) {
if (s_operating_states[i].enabled) {
odr_max = MAX(odr_max, s_operating_states[i].odr);
}
}
uint32_t sample_interval = 0;
switch (odr_max) {
case BMA255ODR_1HZ:
sample_interval = BMA255SampleInterval_1HZ;
break;
case BMA255ODR_10HZ:
sample_interval = BMA255SampleInterval_10HZ;
break;
case BMA255ODR_19HZ:
sample_interval = BMA255SampleInterval_19HZ;
break;
case BMA255ODR_83HZ:
sample_interval = BMA255SampleInterval_83HZ;
break;
case BMA255ODR_125HZ:
sample_interval = BMA255SampleInterval_125HZ;
break;
case BMA255ODR_166HZ:
sample_interval = BMA255SampleInterval_166HZ;
break;
case BMA255ODR_250HZ:
sample_interval = BMA255SampleInterval_250HZ;
break;
default:
WTF;
}
return sample_interval;
}
//! Set the LOW_POWER and LPW registers as required.
//! The LPW register is masked because it contains the sleep duration for our desired ODR.
static void prv_enter_power_mode(BMA255PowerMode mode) {
bma255_write_register(BMA255Register_PMU_LOW_POWER,
s_power_mode[mode].low_power << BMA255_LOW_POWER_SHIFT);
bma255_read_modify_write(BMA255Register_PMU_LPW,
s_power_mode[mode].lpw << BMA255_LPW_POWER_SHIFT,
BMA255_LPW_POWER_MASK);
// Workaround for error in transition to Suspend / Standby
if (mode == BMA255PowerMode_Suspend || mode == BMA255PowerMode_Standby) {
// Write to FIFO_CONFIG_1 to exit some unknown "intermittent state"
// NOTE: This will clear the FIFO & FIFO status.
bma255_read_modify_write(BMA255Register_FIFO_CONFIG_1, 0, 0);
}
}
static void prv_set_accel_power_mode(BMA255PowerMode mode) {
PBL_ASSERTN(mode == BMA255PowerMode_Normal ||
mode == BMA255PowerMode_LowPower1 ||
mode == BMA255PowerMode_Standby);
// Workaround for entering Normal Mode
// LPM1 => Normal requires us to go through Suspend mode
// LPM2 => Normal requires us to go through Standby mode
if (mode == BMA255PowerMode_Normal) {
if (s_accel_power_mode == BMA255PowerMode_LowPower1) {
prv_enter_power_mode(BMA255PowerMode_Suspend);
} else if (s_accel_power_mode == BMA255PowerMode_LowPower2) {
prv_enter_power_mode(BMA255PowerMode_Standby);
}
}
prv_enter_power_mode(mode);
BMA255_DBG("BMA555: power level set to: 0x%x and 0x%x",
bma255_read_register(BMA255Register_PMU_LPW),
bma255_read_register(BMA255Register_PMU_LOW_POWER));
s_accel_power_mode = mode;
}
static BMA255ODR prv_get_odr(BMA255SampleInterval sample_interval) {
BMA255ODR odr = 0;
switch (sample_interval) {
case BMA255SampleInterval_1HZ:
odr = BMA255ODR_1HZ;
break;
case BMA255SampleInterval_10HZ:
odr = BMA255ODR_10HZ;
break;
case BMA255SampleInterval_19HZ:
odr = BMA255ODR_19HZ;
break;
case BMA255SampleInterval_83HZ:
odr = BMA255ODR_83HZ;
break;
case BMA255SampleInterval_125HZ:
odr = BMA255ODR_125HZ;
break;
case BMA255SampleInterval_166HZ:
odr = BMA255ODR_166HZ;
break;
case BMA255SampleInterval_250HZ:
odr = BMA255ODR_250HZ;
break;
default:
WTF;
}
return odr;
}
static BMA255SampleInterval prv_get_supported_sampling_interval(uint32_t interval_us) {
BMA255SampleInterval sample_interval;
if (BMA255SampleInterval_1HZ <= interval_us) {
sample_interval = BMA255SampleInterval_1HZ;
} else if (BMA255SampleInterval_10HZ <= interval_us) {
sample_interval = BMA255SampleInterval_10HZ;
} else if (BMA255SampleInterval_19HZ <= interval_us) {
sample_interval = BMA255SampleInterval_19HZ;
} else if (BMA255SampleInterval_83HZ <= interval_us) {
sample_interval = BMA255SampleInterval_83HZ;
} else if (BMA255SampleInterval_125HZ <= interval_us) {
sample_interval = BMA255SampleInterval_125HZ;
} else if (BMA255SampleInterval_166HZ <= interval_us) {
sample_interval = BMA255SampleInterval_166HZ;
} else if (BMA255SampleInterval_250HZ <= interval_us) {
sample_interval = BMA255SampleInterval_250HZ;
} else {
sample_interval = BMA255SampleInterval_250HZ;
}
return sample_interval;
}
static void prv_enable_operating_mode(AccelOperatingMode mode,
BMA255SampleInterval sample_interval) {
s_operating_states[mode].enabled = true;
s_operating_states[mode].odr = prv_get_odr(sample_interval);
prv_configure_operating_mode();
}
static void prv_disable_operating_mode(AccelOperatingMode mode) {
s_operating_states[mode].enabled = false;
prv_configure_operating_mode();
}
uint32_t accel_set_sampling_interval(uint32_t interval_us) {
BMA255SampleInterval actual_interval = prv_get_supported_sampling_interval(interval_us);
// FIXME: For now, tie us to 125Hz. 125Hz is a rate that is easy enough to
// subsample to all of our supported accel service rates, and also cuts down power consumption
// from the 140uA range to 100uA.
// Being able to sample at a lower rate like 38Hz will be able to get us down into the 40uA range.
//
// By forcing a sample interval of 125Hz here, we will never use a different
// rate, and the accelerometer service will be made aware of our running rate.
actual_interval = BMA255SampleInterval_125HZ;
prv_enable_operating_mode(AccelOperatingMode_Data, actual_interval);
return accel_get_sampling_interval();
}
static void prv_configure_operating_mode(void) {
BMA255SampleInterval interval_us = accel_get_sampling_interval();
const uint8_t odr = (uint8_t)prv_get_odr(interval_us);
const uint8_t bw = s_odr_settings[odr].bw;
const uint8_t tsleep = s_odr_settings[odr].tsleep;
// Set the BW and TSleep to get the ODR we expect.
bma255_write_register(BMA255Register_PMU_BW, bw);
bma255_read_modify_write(BMA255Register_PMU_LPW,
tsleep << BMA255_LPW_SLEEP_DUR_SHIFT,
BMA255_LPW_SLEEP_DUR_MASK);
PBL_LOG(LOG_LEVEL_DEBUG, "Set sampling rate to %"PRIu32, (uint32_t)(1000000/interval_us));
if (s_accel_power_mode == BMA255PowerMode_Normal) {
// This should only execute on startup or if the power mode
// is left in normal power mode for some reason
PBL_LOG(LOG_LEVEL_DEBUG, "Enable low power mode");
prv_set_accel_power_mode(BMA255PowerMode_LowPower1);
}
}
int accel_peek(AccelDriverSample *data) {
prv_read_curr_accel_data(data);
return 0;
}
////////////////////////////////////////////////////////////////////////////////
// FIFO Support
////////////////////////////////////////////////////////////////////////////////
static void prv_program_fifo_register(uint8_t address, uint8_t data) {
// To prevent lockups of the fifo, the fifo config registers should only be programmed
// while in standby mode
PBL_ASSERTN(s_accel_power_mode == BMA255PowerMode_Standby);
const int retries = 2;
uint8_t value;
for (int i = 0; i <= retries; i++) {
bma255_write_register(address, data);
value = bma255_read_register(address);
if (value == data) {
return; // Write took, we are good
}
PBL_LOG(LOG_LEVEL_DEBUG, "FIFO config write failed, initiating workaround ...");
// FIXME: Sometimes writes to the FIFO registers fail. I am suspicious that the bma255 enters
// suspend mode instead of standby mode. (The datasheet states that FIFO_CONFIG registers
// accesses fail in suspend mode). It seems like the issue can be worked around by attempting
// to enter standby mode again. Hopefully, bosch can illuminate for us what is going on here
// but in the meantime let's use this workaround.
prv_set_accel_power_mode(BMA255PowerMode_Normal);
prv_set_accel_power_mode(BMA255PowerMode_Standby);
}
PBL_LOG(LOG_LEVEL_WARNING, "Failed to program fifo reg, 0x%"PRIx8" = 0x%"PRIx8, address, data);
}
static void prv_set_fifo_mode(BMA255FifoMode mode) {
BMA255_DBG("Set Fifo Mode: 0x%x", mode);
const uint8_t out =
(mode << BMA255_FIFO_MODE_SHIFT) | (BMA255FifoDataSel_XYZ << BMA255_FIFO_DATA_SEL_SHIFT);
prv_program_fifo_register(BMA255Register_FIFO_CONFIG_1, out);
// If the fifo had overflowed, the write above will have cleared the flag
s_fifo_overrun_detected = false;
}
static void prv_configure_fifo_interrupts(bool enable_int, bool use_fifo) {
BMA255_DBG("Enabling FIFO Interrupts: %d %d", (int)enable_int, (int)use_fifo);
uint8_t map_value;
uint8_t en_value;
if (!enable_int) {
map_value = 0;
en_value = 0;
} else if (!use_fifo) {
map_value = BMA255_INT_MAP_1_INT2_DATA;
en_value = BMA255_INT_EN_1_DATA;
} else {
map_value = BMA255_INT_MAP_1_INT2_FIFO_WATERMARK;
en_value = BMA255_INT_EN_1_FIFO_WATERMARK;
}
bma255_write_register(BMA255Register_INT_MAP_1, map_value);
bma255_write_register(BMA255Register_INT_EN_1, en_value);
prv_update_accel_interrupts(enable_int, AccelOperatingMode_Data);
}
void accel_set_num_samples(uint32_t num_samples) {
// Disable interrupts so they won't fire while we change sampling rate
prv_configure_fifo_interrupts(false, false);
// Workaround some bma255 issues:
// Need to use Standby Mode to read/write the FIFO_CONFIG registers.
prv_set_accel_power_mode(BMA255PowerMode_Normal); // Need to transition to Normal first
prv_set_accel_power_mode(BMA255PowerMode_Standby);
if (num_samples > BMA255_FIFO_MAX_FRAMES) {
num_samples = BMA255_FIFO_MAX_FRAMES;
}
BMA255_DBG("Setting num samples to: %"PRIu32, num_samples);
// Note that with the bma255, we do not want to use Bypass mode when
// collecting a single sample as this will result in uneven sampling.
// The accelerometer will wake up, provide several samples in quick
// succession, and then go back to sleep for a period. Looking at the INT2
// line shows similar to this:
// _ _ _ _ _ _
// .... ____| |_| |_| |______________________| |_| |_| |_________ .....
//
// By using a FIFO of depth 1, the bma255 respects EST mode and will provide
// samples at a predictable interval and rate.
const bool use_fifo = (num_samples > 0);
if (use_fifo) {
PBL_LOG(LOG_LEVEL_DEBUG, "Enabling FIFO");
// Watermark is the number of samples to be collected
prv_program_fifo_register(BMA255Register_FIFO_CONFIG_0, num_samples);
prv_set_fifo_mode(BMA255FifoMode_Fifo);
} else {
PBL_LOG(LOG_LEVEL_DEBUG, "Disabling FIFO");
prv_set_fifo_mode(BMA255FifoMode_Bypass);
}
prv_set_accel_power_mode(BMA255PowerMode_Normal);
prv_set_accel_power_mode(BMA255PowerMode_LowPower1);
const bool enable_int = (num_samples != 0);
prv_configure_fifo_interrupts(enable_int, use_fifo);
s_fifo_is_enabled = use_fifo;
}
////////////////////////////////////////////////////////////////////////////////
// Shake Detection
////////////////////////////////////////////////////////////////////////////////
static void prv_enable_shake_detection(void) {
bma255_write_register(BMA255Register_INT_EN_0, BMA255_INT_EN_0_SLOPE_X_EN |
BMA255_INT_EN_0_SLOPE_Y_EN |
BMA255_INT_EN_0_SLOPE_Z_EN);
bma255_write_register(BMA255Register_INT_MAP_0, BMA255_INT_MAP_0_INT1_SLOPE);
// configure the anymotion interrupt to fire after 4 successive
// samples are over the threhold specified
accel_set_shake_sensitivity_high(false /* sensitivity_high */);
bma255_write_register(BMA255Register_INT_5,
BMA255_INT_5_SLOPE_DUR_MASK << BMA255_INT_5_SLOPE_DUR_SHIFT);
prv_enable_operating_mode(AccelOperatingMode_ShakeDetection, BMA255SampleInterval_83HZ);
}
static void prv_disable_shake_detection(void) {
// Don't worry about the configuration registers but disable interrupts from the accel
bma255_write_register(BMA255Register_INT_EN_0, 0);
prv_disable_operating_mode(AccelOperatingMode_ShakeDetection);
}
void accel_enable_shake_detection(bool enable) {
if (s_shake_detection_enabled == enable) {
// the requested change matches what we already have!
return;
}
PBL_LOG(LOG_LEVEL_DEBUG, "%s shake detection", enable ? "Enabling" : "Disabling");
prv_update_accel_interrupts(enable, AccelOperatingMode_ShakeDetection);
if (enable) {
prv_enable_shake_detection();
} else {
prv_disable_shake_detection();
}
s_shake_detection_enabled = enable;
}
void accel_set_shake_sensitivity_high(bool sensitivity_high) {
// Configure the threshold level at which the BMI160 will think shake has occurred
if (sensitivity_high) {
bma255_write_register(BMA255Register_INT_6,
BOARD_CONFIG_ACCEL.accel_config.shake_thresholds[AccelThresholdLow]);
} else {
bma255_write_register(BMA255Register_INT_6,
BOARD_CONFIG_ACCEL.accel_config.shake_thresholds[AccelThresholdHigh]);
}
}
bool accel_get_shake_detection_enabled(void) {
return s_shake_detection_enabled;
}
////////////////////////////////////////////////////////////////////////////////
// Selftest Support
////////////////////////////////////////////////////////////////////////////////
static void prv_soft_reset(void) {
bma255_write_register(BMA255Register_BGW_SOFTRESET, BMA255_SOFT_RESET_VALUE);
psleep(4);
}
// Minimum thresholds for axis delta in mgs at 4G scale
static const uint16_t SELFTEST_THRESHOLDS[] = {
[BMA255Axis_X] = 800,
[BMA255Axis_Y] = 800,
[BMA255Axis_Z] = 400,
};
static const char AXIS_NAMES[] = {
[BMA255Axis_X] = 'X',
[BMA255Axis_Y] = 'Y',
[BMA255Axis_Z] = 'Z',
};
static const uint8_t AXIS_REGISTERS[] = {
[BMA255Axis_X] = BMA255Register_ACCD_X_LSB,
[BMA255Axis_Y] = BMA255Register_ACCD_Y_LSB,
[BMA255Axis_Z] = BMA255Register_ACCD_Z_LSB,
};
static int16_t prv_read_axis(BMA255Axis axis, uint8_t *new_data) {
uint8_t raw_buf[2];
bma255_burst_read(AXIS_REGISTERS[axis], raw_buf, sizeof(raw_buf));
int16_t reading = prv_conv_raw_to_12bit(raw_buf);
if (new_data) {
*new_data = raw_buf[0] & 0x01;
}
return reading;
}
static bool prv_selftest_axis(BMA255Axis axis) {
uint8_t axis_bits;
switch (axis) {
case BMA255Axis_X:
axis_bits = 0x01;
break;
case BMA255Axis_Y:
axis_bits = 0x02;
break;
case BMA255Axis_Z:
axis_bits = 0x03;
break;
default:
WTF;
}
// g-range should be 4g for self-test
bma255_set_scale(BMA255Scale_4G);
psleep(2); // wait for a new sample
uint8_t new_data;
int16_t before = prv_read_axis(axis, &new_data);
before = prv_raw_to_mgs(before);
// Positive axis
bma255_write_register(BMA255Register_PMU_SELFTEST, axis_bits | SELFTEST_SIGN_POSITIVE);
psleep(50);
uint8_t new_positive;
int16_t positive = prv_read_axis(axis, &new_positive);
positive = prv_raw_to_mgs(positive);
prv_soft_reset();
bma255_set_scale(BMA255Scale_4G);
// Negative axis
bma255_write_register(BMA255Register_PMU_SELFTEST, axis_bits | SELFTEST_SIGN_NEGATIVE);
psleep(50);
uint8_t new_negative;
int16_t negative = prv_read_axis(axis, &new_negative);
negative = prv_raw_to_mgs(negative);
prv_soft_reset();
int delta = positive - negative;
delta = abs(delta);
PBL_LOG(LOG_LEVEL_DEBUG,
"Self test axis %c: %d Pos: %d Neg: %d Delta: %d (required %d)",
AXIS_NAMES[axis], before, positive,
negative, delta, SELFTEST_THRESHOLDS[axis]);
if (delta < SELFTEST_THRESHOLDS[axis]) {
PBL_LOG(LOG_LEVEL_ERROR, "Self test failed for axis %c: %d < %d",
AXIS_NAMES[axis], delta, SELFTEST_THRESHOLDS[axis]);
return false;
}
if ((new_data + new_negative + new_positive) != 3) {
PBL_LOG(LOG_LEVEL_ERROR, "Self test problem? Not logging data? %d %d %d",
new_data, new_positive, new_negative);
}
return true;
}
bool bma255_selftest(void) {
// calling selftest_axis resets the device
bool pass = true;
pass &= prv_selftest_axis(BMA255Axis_X);
pass &= prv_selftest_axis(BMA255Axis_Y);
pass &= prv_selftest_axis(BMA255Axis_Z);
// g-range should be 4g to copy the BMI160
bma255_set_scale(BMA255Scale_4G);
return pass;
}
bool accel_run_selftest(void) {
return bma255_selftest();
}
////////////////////////////////////////////////////////////////////////////////
// Debug Commands
////////////////////////////////////////////////////////////////////////////////
void command_accel_status(void) {
const uint8_t bw = bma255_read_register(BMA255Register_PMU_BW);
const uint8_t lpw = bma255_read_register(BMA255Register_PMU_LPW);
const uint8_t lp = bma255_read_register(BMA255Register_PMU_LOW_POWER);
const uint8_t fifo_cfg0 = bma255_read_register(BMA255Register_FIFO_CONFIG_0);
const uint8_t fifo_cfg1 = bma255_read_register(BMA255Register_FIFO_CONFIG_1);
const uint8_t fifo_status = bma255_read_register(BMA255Register_FIFO_STATUS);
const uint8_t int_map_0 = bma255_read_register(BMA255Register_INT_MAP_0);
const uint8_t int_en_0 = bma255_read_register(BMA255Register_INT_EN_0);
const uint8_t int_map_1 = bma255_read_register(BMA255Register_INT_MAP_1);
const uint8_t int_en_1 = bma255_read_register(BMA255Register_INT_EN_1);
const uint8_t int_map_2 = bma255_read_register(BMA255Register_INT_MAP_2);
const uint8_t int_en_2 = bma255_read_register(BMA255Register_INT_EN_2);
const uint8_t int_status_0 = bma255_read_register(BMA255Register_INT_STATUS_0);
const uint8_t int_status_1 = bma255_read_register(BMA255Register_INT_STATUS_1);
const uint8_t int_status_2 = bma255_read_register(BMA255Register_INT_STATUS_2);
const uint8_t int_status_3 = bma255_read_register(BMA255Register_INT_STATUS_3);
char buf[64];
prompt_send_response_fmt(buf, 64, "(0x10) Bandwidth: 0x%"PRIx8, bw);
prompt_send_response_fmt(buf, 64, "(0x11) LPW: 0x%"PRIx8, lpw);
prompt_send_response_fmt(buf, 64, " suspend: 0x%"PRIx8, (lpw & (1 << 7)) != 0);
prompt_send_response_fmt(buf, 64, " lowpower_en: 0x%"PRIx8, (lpw & (1 << 6)) != 0);
prompt_send_response_fmt(buf, 64, " deep_suspend: 0x%"PRIx8, (lpw & (1 << 5)) != 0);
prompt_send_response_fmt(buf, 64, " sleep_dur: 0x%"PRIx8, (lpw & 0b11110) >> 1);
prompt_send_response_fmt(buf, 64, "(0x12) Low_Power: 0x%"PRIx8, lp);
prompt_send_response_fmt(buf, 64, " lowpower_mode: 0x%"PRIx8, (lp & (1 << 6)) != 0);
prompt_send_response_fmt(buf, 64, " sleeptimer_mode: 0x%"PRIx8, (lp & (1 << 5)) != 0);
prompt_send_response_fmt(buf, 64, "(0x30) FIFO Config 0: 0x%"PRIx8, fifo_cfg0);
prompt_send_response_fmt(buf, 64, " Watermark: 0x%"PRIx8, fifo_cfg0 & 0b111111);
prompt_send_response_fmt(buf, 64, "(0x3e) FIFO Config 1: 0x%"PRIx8, fifo_cfg1);
prompt_send_response_fmt(buf, 64, " Mode: 0x%"PRIx8, (fifo_cfg1 & (0x3 << 6)) >> 6);
prompt_send_response_fmt(buf, 64, " Data Select: 0x%"PRIx8, fifo_cfg1 & 0x3);
prompt_send_response_fmt(buf, 64, "(0x0e) Fifo Status: 0x%"PRIx8, fifo_status);
prompt_send_response_fmt(buf, 64, " Num Samples: 0x%"PRIx8, (fifo_status & 0x3f));
prompt_send_response_fmt(buf, 64, "(0x19) Int Map 0: 0x%"PRIx8, int_map_0);
prompt_send_response_fmt(buf, 64, "(0x16) Int EN 0: 0x%"PRIx8, int_en_0);
prompt_send_response_fmt(buf, 64, "(0x1a) Int Map 1: 0x%"PRIx8, int_map_1);
prompt_send_response_fmt(buf, 64, "(0x17) Int EN 1: 0x%"PRIx8, int_en_1);
prompt_send_response_fmt(buf, 64, "(0x1b) Int Map 2: 0x%"PRIx8, int_map_2);
prompt_send_response_fmt(buf, 64, "(0x18) Int EN 2: 0x%"PRIx8, int_en_2);
prompt_send_response_fmt(buf, 64, "(0x0a) Int Status 0: 0x%"PRIx8, int_status_0);
prompt_send_response_fmt(buf, 64, "(0x0a) Int Status 1: 0x%"PRIx8, int_status_1);
prompt_send_response_fmt(buf, 64, "(0x0b) Int Status 2: 0x%"PRIx8, int_status_2);
prompt_send_response_fmt(buf, 64, "(0x0c) Int Status 3: 0x%"PRIx8, int_status_3);
}
void command_accel_selftest(void) {
const bool success = accel_run_selftest();
char *response = (success) ? "Pass" : "Fail";
prompt_send_response(response);
}
void command_accel_softreset(void) {
prv_soft_reset();
}

View file

@ -0,0 +1,129 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
void bma255_init(void);
bool bma255_query_whoami(void);
//! Power Modes
//! These are the supported power modes, and some rough estimates on power consumption.
//! There is a small set of transitions between power modes that are supported. To make life
//! easy, we will always go through Normal Mode, which allows transition to/from all power modes.
//! Use this enum to index into the \ref s_power_mode table, which contains configurations for each.
typedef enum {
BMA255PowerMode_Normal = 0, // 130uA
BMA255PowerMode_Suspend, // 2.1uA
BMA255PowerMode_Standby, // 62uA
BMA255PowerMode_DeepSuspend, // 1uA
BMA255PowerMode_LowPower1,
BMA255PowerMode_LowPower2,
BMA255PowerModeCount
} BMA255PowerMode;
//! Tsleep values.
//! These are defined to the value we pur into the PMU_LPW register.
//! See Table 3 of datasheet: "Sleep Phase Duration"
typedef enum {
BMA255SleepDuration_0p5ms = 5,
BMA255SleepDuration_1ms = 6,
BMA255SleepDuration_2ms = 7,
BMA255SleepDuration_4ms = 8,
BMA255SleepDuration_6ms = 9,
BMA255SleepDuration_10ms = 10,
BMA255SleepDuration_25ms = 11,
BMA255SleepDuration_50ms = 12,
BMA255SleepDuration_100ms = 13,
BMA255SleepDuration_500ms = 14,
BMA255SleepDuration_1000ms = 15,
BMA255SleepDurationCount
} BMA255SleepDuration;
//! These are the natively supported filter bandwidths of the bma255.
//! Note that power consumption is tightly tied to the filter bandwidth. In
//! order to run acceptably, we need to keep a bandwidth up in the 500Hz ~ 1kHz range.
//! Please see discussion below for more information on Bandwith, TSleep and ODR.
typedef enum {
BMA255Bandwidth_7p81HZ = 8,
BMA255Bandwidth_15p63HZ = 9,
BMA255Bandwidth_31p25HZ = 10,
BMA255Bandwidth_62p5HZ = 11,
BMA255Bandwidth_125HZ = 12,
BMA255Bandwidth_250HZ = 13,
BMA255Bandwidth_500HZ = 14,
BMA255Bandwidth_1000HZ = 15,
BMA255BandwidthCount
} BMA255Bandwidth;
//! In order to acheive low power consumptions, the BMA255 Output Data Rate (ODR)
//! is determined by a combination of:
//! - high-bandwidth operating rate:
//! Less filtering is done on the bma255, which has a direct impact on power consumption.
//! This gives a lower "update time", which in turn means less "active time" of the device.
//! The trade-off here is that accelerometer data is a bit more susceptible to noise.
//! - sleep time:
//! The longer the sleep duration, the less power the device consums.
//! After tsleep ms, a sample is taken, and then the device goes back to sleep.
//!
//! Power measurements on the board have shown we ideally want to run at a BW of 500Hz or 1000Hz.
//! Unfortunately, there is an issue with data jumps when running in low power modes.
//! At 4G sensitivity, we need to run at a bandwidth lower than 500Hz in order to minimize
//! jitter in readings. This means we probably want to stay at 250Hz.
//!
//! We are using Equidistant Sampling Mode (EST) to ensure that samples are taken
//! at equal time distances. See Figure 4 in the datasheet for an explanation of this.
//! In EST, a sample is taken every tsample ms, where tsample = (tsleep + wkup_time) [1]
//!
//! We can _approximate_ actual ODR as the following: [2]
//! ODR = (1000 / (tsleep + wkup_time))
//! where tsleep holds the property that:
//! N = (2 * bw) * (tsleep / 1000) such that N is an Integer. [3][4]
//! and wkup_time is taken for the corresponding bandwidth from Table 4 of the datasheet.
//!
//! [1] This is the best we can gather as a good approximation after a meeting with Bosch.
//! [2] This is only an approximation as the BMA255 part is only guaranteed to have
//! Bandwidth accuracy within +/- 10%
//! [3] See p.16 of datasheet. Note that the formula in the datasheet is confirmed wrong by Bosch.
//! [4] Take note that all tsleep values are supported when running at 500Hz
//!
typedef enum {
BMA255ODR_1HZ = 0,
BMA255ODR_10HZ,
BMA255ODR_19HZ,
BMA255ODR_83HZ,
BMA255ODR_125HZ,
BMA255ODR_166HZ,
BMA255ODR_250HZ,
BMA255ODRCount
} BMA255ODR;
//! Note that these sample intervals are approximations.
typedef enum {
BMA255SampleInterval_1HZ = (1000000 / 1),
BMA255SampleInterval_10HZ = (1000000 / 10),
BMA255SampleInterval_19HZ = (1000000 / 19),
BMA255SampleInterval_83HZ = (1000000 / 83),
BMA255SampleInterval_125HZ = (1000000 / 125),
BMA255SampleInterval_166HZ = (1000000 / 166),
BMA255SampleInterval_250HZ = (1000000 / 250),
} BMA255SampleInterval;

View file

@ -0,0 +1,49 @@
/*
* 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.
*/
#pragma once
#include "board/board.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/spi.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#include <mcu.h>
bool bma255_selftest(void);
void bma255_gpio_init(void);
void bma255_enable_spi_clock(void);
void bma255_disable_spi_clock(void);
uint8_t bma255_send_and_receive_byte(uint8_t byte);
void bma255_send_byte(uint8_t byte);
void bma255_prepare_txn(uint8_t address);
void bma255_end_txn(void);
void bma255_burst_read(uint8_t address, uint8_t *data, size_t len);
uint8_t bma255_read_register(uint8_t address);
void bma255_write_register(uint8_t address, uint8_t data);
void bma255_read_modify_write(uint8_t reg, uint8_t value, uint8_t mask);

View file

@ -0,0 +1,188 @@
/*
* 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.
*/
#pragma once
#include "bma255.h"
#include "util/attributes.h"
#include <inttypes.h>
// Read & Write flags to be masked onto register addresses for raw spi transactions
static const uint8_t BMA255_READ_FLAG = 0x80;
static const uint8_t BMA255_WRITE_FLAG = 0x00;
// BMI255 Register Map
typedef enum {
BMA255Register_BGW_CHIP_ID = 0x00,
BMA255Register_ACCD_X_LSB = 0x02,
BMA255Register_ACCD_X_MSB = 0x03,
BMA255Register_ACCD_Y_LSB = 0x04,
BMA255Register_ACCD_Y_MSB = 0x05,
BMA255Register_ACCD_Z_LSB = 0x06,
BMA255Register_ACCD_Z_MSB = 0x07,
BMA255Register_ACCD_TEMP = 0x08,
BMA255Register_INT_STATUS_0 = 0x09,
BMA255Register_INT_STATUS_1 = 0x0a,
BMA255Register_INT_STATUS_2 = 0x0b,
BMA255Register_INT_STATUS_3 = 0x0c,
BMA255Register_FIFO_STATUS = 0x0e,
BMA255Register_PMU_RANGE = 0x0f,
BMA255Register_PMU_BW = 0x10,
BMA255Register_PMU_LPW = 0x11,
BMA255Register_PMU_LOW_POWER = 0x12,
BMA255Register_ACCD_HBW = 0x13,
BMA255Register_BGW_SOFTRESET = 0x14,
BMA255Register_INT_EN_0 = 0x16,
BMA255Register_INT_EN_1 = 0x17,
BMA255Register_INT_EN_2 = 0x18,
BMA255Register_INT_MAP_0 = 0x19,
BMA255Register_INT_MAP_1 = 0x1a,
BMA255Register_INT_MAP_2 = 0x1b,
BMA255Register_INT_SRC = 0x1e,
BMA255Register_INT_OUT_CTRL = 0x20,
BMA255Register_INT_RST_LATCH = 0x21,
BMA255Register_INT_0 = 0x22,
BMA255Register_INT_1 = 0x23,
BMA255Register_INT_2 = 0x24,
BMA255Register_INT_3 = 0x25,
BMA255Register_INT_4 = 0x26,
BMA255Register_INT_5 = 0x27,
BMA255Register_INT_6 = 0x28,
BMA255Register_INT_7 = 0x29,
BMA255Register_INT_8 = 0x2a,
BMA255Register_INT_9 = 0x2b,
BMA255Register_INT_a = 0x2c,
BMA255Register_INT_b = 0x2d,
BMA255Register_INT_c = 0x2e,
BMA255Register_INT_d = 0x2f,
BMA255Register_FIFO_CONFIG_0 = 0x30,
BMA255Register_PMU_SELFTEST = 0x32,
BMA255Register_TRIM_NVM_CTRL = 0x33,
BMA255Register_BGW_SPI3_WDT = 0x34,
BMA255Register_OFC_CTRL = 0x36,
BMA255Register_OFC_SETTINGS = 0x37,
BMA255Register_OFC_OFFSET_X = 0x38,
BMA255Register_OFC_OFFSET_Y = 0x39,
BMA255Register_OFC_OFFSET_Z = 0x3a,
BMA255Register_TRIM_GPO0 = 0x3b,
BMA255Register_TRIM_GP1 = 0x3c,
BMA255Register_FIFO_CONFIG_1 = 0x3e,
BMA255Register_FIFO_DATA = 0x3f,
BMA255Register_EXTENDED_MEMORY_MAP = 0x35,
BMA255Register_TEMPERATURE_SENSOR_CTRL = 0x4f,
} BMA255Register;
static const uint8_t BMA255_EXTENDED_MEMORY_MAP_OPEN = 0xca;
static const uint8_t BMA255_EXTENDED_MEMORY_MAP_CLOSE = 0x0a;
static const uint8_t BMA255_TEMPERATURE_SENSOR_DISABLE = 0x0;
static const uint8_t BMA255_CHIP_ID = 0xfa;
static const uint8_t BMA255_ACC_CONF_PMU_BW_MASK = 0x1f;
static const uint8_t BMA255_SOFT_RESET_VALUE = 0xb6;
static const uint8_t BMA255_FIFO_MODE_SHIFT = 6;
static const uint8_t BMA255_FIFO_MODE_MASK = 0xc0;
static const uint8_t BMA255_FIFO_DATA_SEL_SHIFT = 0;
static const uint8_t BMA255_FIFO_DATA_SEL_MASK = 0x03;
static const uint8_t BMA255_INT_STATUS_0_SLOPE_MASK = (1 << 2);
static const uint8_t BMA255_INT_STATUS_2_SLOPE_SIGN = (1 << 3);
static const uint8_t BMA255_INT_STATUS_2_SLOPE_FIRST_X = (1 << 0);
static const uint8_t BMA255_INT_STATUS_2_SLOPE_FIRST_Y = (1 << 1);
static const uint8_t BMA255_INT_STATUS_2_SLOPE_FIRST_Z = (1 << 2);
static const uint8_t BMA255_INT_MAP_1_INT2_FIFO_FULL = (0x1 << 5);
static const uint8_t BMA255_INT_MAP_1_INT2_FIFO_WATERMARK = (0x1 << 6);
static const uint8_t BMA255_INT_MAP_1_INT2_DATA = (0x1 << 7);
static const uint8_t BMA255_INT_MAP_0_INT1_SLOPE = (0x1 << 2);
static const uint8_t BMA255_INT_EN_0_SLOPE_X_EN = (1 << 0);
static const uint8_t BMA255_INT_EN_0_SLOPE_Y_EN = (1 << 1);
static const uint8_t BMA255_INT_EN_0_SLOPE_Z_EN = (1 << 2);
static const uint8_t BMA255_INT_EN_1_DATA = (0x1 << 4);
static const uint8_t BMA255_INT_EN_1_FIFO_FULL = (0x1 << 5);
static const uint8_t BMA255_INT_EN_1_FIFO_WATERMARK = (0x1 << 6);
static const uint8_t BMA255_INT_5_SLOPE_DUR_SHIFT = 0;
static const uint8_t BMA255_INT_5_SLOPE_DUR_MASK = 0x3;
static const uint8_t BMA255_LPW_SLEEP_DUR_SHIFT = 1;
static const uint8_t BMA255_LPW_SLEEP_DUR_MASK = (0xf << 1);
static const uint8_t BMA255_LPW_POWER_SHIFT = 5;
static const uint8_t BMA255_LPW_POWER_MASK = (0x7 << 5);
static const uint8_t BMA255_LOW_POWER_SHIFT = 5;
static const uint8_t BMA255_LOW_POWER_MASK = (0x3 << 5);
typedef struct PACKED {
uint16_t x;
uint16_t y;
uint16_t z;
} BMA255AccelData;
typedef enum {
BMA255FifoMode_Bypass = 0x00,
BMA255FifoMode_Fifo = 0x01,
BMA255FifoMode_Stream = 0x02,
} BMA255FifoMode;
typedef enum {
BMA255FifoDataSel_XYZ = 0x00,
BMA255FifoDataSel_X = 0x01,
BMA255FifoDataSel_Y = 0x02,
BMA255FifoDataSel_Z = 0x03,
} BMA255FifoDataSel;
//! Configuration to be used to enter each of the supported power modes.
//! Make sure that the PMU_LOW_POWER register is always set prior to the PMU_LPW
//! register, as the bma255 uses this restriction.
static const struct {
uint8_t low_power; //!< PMU_LOW_POWER register
uint8_t lpw; //!< PMU_LPW register
} s_power_mode[BMA255PowerModeCount] = {
[BMA255PowerMode_Normal] = { .low_power = 0x0, .lpw = 0x0 },
[BMA255PowerMode_Suspend] = { .low_power = 0x0, .lpw = 0x4 },
[BMA255PowerMode_Standby] = { .low_power = 0x2, .lpw = 0x4 },
[BMA255PowerMode_DeepSuspend] = { .low_power = 0x0, .lpw = 0x1 },
[BMA255PowerMode_LowPower1] = { .low_power = 0x1, .lpw = 0x2 },
[BMA255PowerMode_LowPower2] = { .low_power = 0x3, .lpw = 0x2 },
};
//! Configuration to be used for each ODR we will be using.
//! This involves some native bma255 bandwidth and a tsleep value.
//! Errata states that at 4G sensitivity, we need to run at a bandwidth of 250HZ or lower.
//! See the discussion around \ref BMA255ODR for more information.
static const struct {
BMA255Bandwidth bw;
BMA255SleepDuration tsleep;
} s_odr_settings[BMA255ODRCount] = {
[BMA255ODR_1HZ] = { BMA255Bandwidth_250HZ, BMA255SleepDuration_1000ms },
[BMA255ODR_10HZ] = { BMA255Bandwidth_250HZ, BMA255SleepDuration_100ms },
[BMA255ODR_19HZ] = { BMA255Bandwidth_250HZ, BMA255SleepDuration_50ms },
[BMA255ODR_83HZ] = { BMA255Bandwidth_250HZ, BMA255SleepDuration_10ms },
[BMA255ODR_125HZ] = { BMA255Bandwidth_250HZ, BMA255SleepDuration_6ms },
[BMA255ODR_166HZ] = { BMA255Bandwidth_250HZ, BMA255SleepDuration_4ms },
[BMA255ODR_250HZ] = { BMA255Bandwidth_250HZ, BMA255SleepDuration_2ms },
};

View file

@ -0,0 +1,158 @@
/*
* 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 "board/board.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/rtc.h"
#include "drivers/spi.h"
#include "kernel/util/sleep.h"
#include "util/units.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#include <mcu.h>
#include "bma255_private.h"
#include "bma255_regs.h"
#define BMA255_SPI SPI3
static const uint32_t BMA255_PERIPH_CLOCK = RCC_APB1Periph_SPI3;
static const SpiPeriphClock BMA255_SPI_CLOCK = SpiPeriphClockAPB1;
static const AfConfig BMA255_SCLK_CONFIG = { GPIOB, GPIO_Pin_12, GPIO_PinSource12, GPIO_AF7_SPI3 };
static const AfConfig BMA255_MISO_CONFIG = { GPIOC, GPIO_Pin_11, GPIO_PinSource11, GPIO_AF_SPI3 };
static const AfConfig BMA255_MOSI_CONFIG = { GPIOC, GPIO_Pin_12, GPIO_PinSource12, GPIO_AF_SPI3 };
static const OutputConfig BMA255_SCS_CONFIG = { GPIOA, GPIO_Pin_4, false };
// Need to wait a minimum of 450µs after a write.
// Due to RTC resolution, we need to make sure that the tick counter has
// incremented twice so we can be certain at least one full tick-period has elapsed.
#define MIN_TICKS_AFTER_WRITE 2
static RtcTicks s_last_write_ticks = 0;
_Static_assert(RTC_TICKS_HZ < (1000000 / 450), "Tick period < 450µs");
void bma255_gpio_init(void) {
periph_config_acquire_lock();
gpio_af_init(&BMA255_SCLK_CONFIG, GPIO_OType_PP, GPIO_Speed_50MHz, GPIO_PuPd_NOPULL);
gpio_af_init(&BMA255_MISO_CONFIG, GPIO_OType_PP, GPIO_Speed_50MHz, GPIO_PuPd_NOPULL);
gpio_af_init(&BMA255_MOSI_CONFIG, GPIO_OType_PP, GPIO_Speed_50MHz, GPIO_PuPd_NOPULL);
gpio_output_init(&BMA255_SCS_CONFIG, GPIO_OType_PP, GPIO_Speed_50MHz);
SPI_InitTypeDef spi_cfg;
SPI_I2S_DeInit(BMA255_SPI);
spi_cfg.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi_cfg.SPI_Mode = SPI_Mode_Master;
spi_cfg.SPI_DataSize = SPI_DataSize_8b;
spi_cfg.SPI_CPOL = SPI_CPOL_Low;
spi_cfg.SPI_CPHA = SPI_CPHA_1Edge;
spi_cfg.SPI_NSS = SPI_NSS_Soft;
// Max SCLK frequency for the BMA255 is 10 MHz
spi_cfg.SPI_BaudRatePrescaler = spi_find_prescaler(MHZ_TO_HZ(5), BMA255_SPI_CLOCK);
spi_cfg.SPI_FirstBit = SPI_FirstBit_MSB;
spi_cfg.SPI_CRCPolynomial = 7;
bma255_enable_spi_clock();
SPI_Init(BMA255_SPI, &spi_cfg);
SPI_Cmd(BMA255_SPI, ENABLE);
bma255_disable_spi_clock();
periph_config_release_lock();
}
void bma255_enable_spi_clock(void) {
periph_config_enable(BMA255_SPI, BMA255_PERIPH_CLOCK);
}
void bma255_disable_spi_clock(void) {
periph_config_disable(BMA255_SPI, BMA255_PERIPH_CLOCK);
}
uint8_t bma255_send_and_receive_byte(uint8_t byte) {
// Ensure that there are no other write operations in progress
while (SPI_I2S_GetFlagStatus(SPI3, SPI_I2S_FLAG_TXE) == RESET) {}
// Send the byte on the SPI bus
SPI_I2S_SendData(BMA255_SPI, byte);
// Wait for the response byte to be received
while (SPI_I2S_GetFlagStatus(BMA255_SPI, SPI_I2S_FLAG_RXNE) == RESET) {}
// Return the byte
return SPI_I2S_ReceiveData(BMA255_SPI);
}
void bma255_send_byte(uint8_t byte) {
// Ensure that there are no other write operations in progress
while (SPI_I2S_GetFlagStatus(SPI3, SPI_I2S_FLAG_TXE) == RESET) {}
// Send the byte on the SPI bus
SPI_I2S_SendData(BMA255_SPI, byte);
}
//! Set SCS for transaction, start spi clock, and send address
void bma255_prepare_txn(uint8_t address) {
while (rtc_get_ticks() < (s_last_write_ticks + MIN_TICKS_AFTER_WRITE)) {
psleep(1);
}
gpio_output_set(&BMA255_SCS_CONFIG, true);
bma255_enable_spi_clock();
bma255_send_and_receive_byte(address);
}
//! Disables spi clock and sets SCS to end txn
void bma255_end_txn(void) {
bma255_disable_spi_clock();
gpio_output_set(&BMA255_SCS_CONFIG, false);
}
void bma255_burst_read(uint8_t address, uint8_t *data, size_t len) {
const uint8_t reg = address | BMA255_READ_FLAG;
bma255_prepare_txn(reg);
for (size_t i = 0; i < len; ++i) {
data[i] = bma255_send_and_receive_byte(0);
}
bma255_end_txn();
}
uint8_t bma255_read_register(uint8_t address) {
const uint8_t reg = address | BMA255_READ_FLAG;
bma255_prepare_txn(reg);
// Read data
uint8_t data = bma255_send_and_receive_byte(0);
bma255_end_txn();
return data;
}
void bma255_write_register(uint8_t address, uint8_t data) {
const uint8_t reg = address | BMA255_WRITE_FLAG;
bma255_prepare_txn(reg);
bma255_send_and_receive_byte(data);
bma255_end_txn();
s_last_write_ticks = rtc_get_ticks();
}
void bma255_read_modify_write(uint8_t reg, uint8_t value, uint8_t mask) {
uint8_t new_val = bma255_read_register(reg);
new_val &= ~mask;
new_val |= value;
bma255_write_register(reg, new_val);
}

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,36 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
typedef enum {
BMI160_Accel_Mode_Suspend = 0b00,
BMI160_Accel_Mode_Normal = 0b01,
BMI160_Accel_Mode_Low = 0b10,
} BMI160AccelPowerMode;
typedef enum {
BMI160_Gyro_Mode_Suspend = 0b00,
BMI160_Gyro_Mode_Normal = 0b01,
BMI160_Gyro_Mode_FastStartup = 0b11
} BMI160GyroPowerMode;
void bmi160_init(void);
bool bmi160_query_whoami(void);
void bmi160_set_accel_power_mode(BMI160AccelPowerMode mode);
void bmi160_set_gyro_power_mode(BMI160GyroPowerMode mode);

View file

@ -0,0 +1,30 @@
/*
* 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.
*/
#pragma once
#include "board/board.h"
#include "drivers/gpio.h"
#include "drivers/periph_config.h"
#include "drivers/spi.h"
//! Ask the chip to accept input from the SPI bus. Required after issuing a soft reset.
void bmi160_enable_spi_mode(void);
void bmi160_begin_burst(uint8_t addr);
void bmi160_end_burst(void);
uint8_t bmi160_read_reg(uint8_t reg);
uint16_t bmi160_read_16bit_reg(uint8_t reg);
void bmi160_write_reg(uint8_t reg, uint8_t value);

View file

@ -0,0 +1,333 @@
/*
* 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.
*/
#pragma once
#include <inttypes.h>
// BMI160 Register Map
static const uint8_t BMI160_REG_CHIP_ID = 0x00;
static const uint8_t BMI160_REG_ERR = 0x02;
static const uint8_t BMI160_REG_PMU_STATUS = 0x03;
// Current sensor data
static const uint8_t BMI160_REG_DATA_0 = 0x04;
// Register names differ from those in datasheet
static const uint8_t BMI160_REG_MAG_X_LSB = 0x04;
static const uint8_t BMI160_REG_MAG_X_MSB = 0x05;
static const uint8_t BMI160_REG_MAG_Y_LSB = 0x06;
static const uint8_t BMI160_REG_MAG_Y_MSB = 0x07;
static const uint8_t BMI160_REG_MAG_Z_LSB = 0x08;
static const uint8_t BMI160_REG_MAG_Z_MSB = 0x09;
static const uint8_t BMI160_REG_RHALL_LSB = 0x0A;
static const uint8_t BMI160_REG_RHALL_MSB = 0x0B;
static const uint8_t BMI160_REG_GYR_X_LSB = 0x0C;
static const uint8_t BMI160_REG_GYR_X_MSB = 0x0D;
static const uint8_t BMI160_REG_GYR_Y_LSB = 0x0E;
static const uint8_t BMI160_REG_GYR_Y_MSB = 0x0F;
static const uint8_t BMI160_REG_GYR_Z_LSB = 0x10;
static const uint8_t BMI160_REG_GYR_Z_MSB = 0x11;
static const uint8_t BMI160_REG_ACC_X_LSB = 0x12;
static const uint8_t BMI160_REG_ACC_X_MSB = 0x13;
static const uint8_t BMI160_REG_ACC_Y_LSB = 0x14;
static const uint8_t BMI160_REG_ACC_Y_MSB = 0x15;
static const uint8_t BMI160_REG_ACC_Z_LSB = 0x16;
static const uint8_t BMI160_REG_ACC_Z_MSB = 0x17;
// Sensor time is stored in 24-bit little-endian format (LSB in BMI160_REG_SENSORTIME_0)
static const uint8_t BMI160_REG_SENSORTIME_0 = 0x18;
static const uint8_t BMI160_REG_SENSORTIME_1 = 0x19;
static const uint8_t BMI160_REG_SENSORTIME_2 = 0x1A;
static const uint8_t BMI160_SENSORTIME_RESOLUTION_US = 39;
// Status registers
static const uint8_t BMI160_REG_STATUS = 0x1B;
static const uint8_t BMI160_REG_INT_STATUS_0 = 0x1C;
static const uint8_t BMI160_REG_INT_STATUS_1 = 0x1D;
static const uint8_t BMI160_REG_INT_STATUS_2 = 0x1E;
static const uint8_t BMI160_REG_INT_STATUS_3 = 0x1F;
static const uint8_t BMI160_REG_TEMPERATURE_LSB = 0x20;
static const uint8_t BMI160_REG_TEMPERATURE_MSB = 0x21;
// FIFO
static const uint8_t BMI160_REG_FIFO_LENGTH_LSB = 0x22;
static const uint8_t BMI160_REG_FIFO_LENGTH_MSB = 0x23;
static const uint8_t BMI160_REG_FIFO_DOWNS = 0x45;
static const uint8_t BMI160_REG_FIFO_CONFIG_0 = 0x46;
static const uint8_t BMI160_REG_FIFO_CONFIG_1 = 0x47;
static const uint8_t BMI160_REG_FIFO_DATA = 0x24;
static const uint8_t BMI160_REG_ACC_CONF = 0x40;
static const uint8_t BMI160_REG_ACC_RANGE = 0x41;
static const uint8_t BMI160_REG_GYR_CONF = 0x42;
static const uint8_t BMI160_REG_GYR_RANGE = 0x43;
static const uint8_t BMI160_REG_MAG_CONF = 0x44;
// Magnetometer interface configuration
static const uint8_t BMI160_REG_MAG_I2C_DEVICE_ADDR = 0x4B;
static const uint8_t BMI160_REG_MAG_IF_1 = 0x4C;
static const uint8_t BMI160_MAG_IF_1_MANUAL_MODE_ENABLE = 0x80;
static const uint8_t BMI160_REG_MAG_READ_ADDR = 0x4D;
static const uint8_t BMI160_REG_MAG_WRITE_ADDR = 0x4E;
static const uint8_t BMI160_REG_MAG_WRITE_DATA = 0x4F;
// Interrupt configuration
static const uint8_t BMI160_REG_INT_EN_0 = 0x50;
static const uint8_t BMI160_REG_INT_EN_1 = 0x51;
static const uint8_t BMI160_REG_INT_EN_2 = 0x52;
static const uint8_t BMI160_REG_INT_OUT_CTRL = 0x53;
static const uint8_t BMI160_REG_INT_LATCH = 0x54;
static const uint8_t BMI160_REG_INT_MAP_0 = 0x55;
static const uint8_t BMI160_REG_INT_MAP_1 = 0x56;
static const uint8_t BMI160_REG_INT_MAP_2 = 0x57;
static const uint8_t BMI160_REG_INT_DATA_0 = 0x58;
static const uint8_t BMI160_REG_INT_DATA_1 = 0x59;
static const uint8_t BMI160_REG_INT_LOWHIGH_0 = 0x5A;
static const uint8_t BMI160_REG_INT_LOWHIGH_1 = 0x5B;
static const uint8_t BMI160_REG_INT_LOWHIGH_2 = 0x5C;
static const uint8_t BMI160_REG_INT_LOWHIGH_3 = 0x5D;
static const uint8_t BMI160_REG_INT_LOWHIGH_4 = 0x5E;
static const uint8_t BMI160_REG_INT_MOTION_0 = 0x5F;
static const uint8_t BMI160_REG_INT_MOTION_1 = 0x60;
static const uint8_t BMI160_REG_INT_MOTION_2 = 0x61;
static const uint8_t BMI160_REG_INT_MOTION_3 = 0x62;
static const uint8_t BMI160_REG_INT_TAP_0 = 0x63;
static const uint8_t BMI160_REG_INT_TAP_1 = 0x64;
static const uint8_t BMI160_REG_INT_ORIENT_0 = 0x65;
static const uint8_t BMI160_REG_INT_ORIENT_1 = 0x66;
static const uint8_t BMI160_REG_INT_FLAT_0 = 0x67;
static const uint8_t BMI160_REG_INT_FLAT_1 = 0x68;
static const uint8_t BMI160_REG_FOC_CONF = 0x69;
static const uint8_t BMI160_REG_CONF = 0x6A;
static const uint8_t BMI160_REG_IF_CONF = 0x6B;
static const uint8_t BMI160_IF_CONF_MAG_ENABLE = 0x20; // Undocumented
static const uint8_t BMI160_REG_PMU_TRIGGER = 0x6C;
static const uint8_t BMI160_REG_SELF_TEST = 0x6D;
static const uint8_t BMI160_REG_NV_CONF = 0x70;
static const uint8_t BMI160_REG_OFFSET_ACC_X = 0x71;
static const uint8_t BMI160_REG_OFFSET_ACC_Y = 0x72;
static const uint8_t BMI160_REG_OFFSET_ACC_Z = 0x73;
static const uint8_t BMI160_REG_OFFSET_GYR_X_LSB = 0x74;
static const uint8_t BMI160_REG_OFFSET_GYR_Y_LSB = 0x75;
static const uint8_t BMI160_REG_OFFSET_GYR_Z_LSB = 0x76;
static const uint8_t BMI160_REG_OFFSET_7 = 0x77;
static const uint8_t BMI160_REG_STEPCOUNTER_LSB = 0x78;
static const uint8_t BMI160_REG_STEPCOUNTER_MSB = 0x79;
static const uint8_t BMI160_REG_INT_STEP_DET_CONF_0 = 0x7A;
static const uint8_t BMI160_REG_STEPCOUNTER_CONF = 0x7B;
static const uint8_t BMI160_REG_CMD = 0x7E;
static const uint8_t BMI160_CMD_START_FOC = 0x03;
// To set the PMU mode, bitwise-or the command with the desired mode
// from the BMI160*PowerMode enums.
static const uint8_t BMI160_CMD_ACC_SET_PMU_MODE = 0x10;
static const uint8_t BMI160_CMD_GYR_SET_PMU_MODE = 0x14;
static const uint8_t BMI160_CMD_MAG_SET_PMU_MODE = 0x18;
static const uint8_t BMI160_CMD_PROG_NVM = 0xA0;
static const uint8_t BMI160_CMD_FIFO_FLUSH = 0xB0;
static const uint8_t BMI160_CMD_INT_RESET = 0xB1;
static const uint8_t BMI160_CMD_SOFTRESET = 0xB6;
static const uint8_t BMI160_CMD_STEP_CNT_CLR = 0xB2;
// Command sequence to enable "extended mode"
static const uint8_t BMI160_CMD_EXTMODE_EN_FIRST = 0x37;
static const uint8_t BMI160_CMD_EXTMODE_EN_MIDDLE = 0x9A;
static const uint8_t BMI160_CMD_EXTMODE_EN_LAST = 0xc0;
// Extended mode register; see Bosch Android driver
static const uint8_t BMI160_REG_EXT_MODE = 0x7F;
static const uint8_t BMI160_EXT_MODE_PAGING_EN = 0x80;
static const uint8_t BMI160_EXT_MODE_TARGET_PAGE_1 = 0x10;
// Constants
static const uint8_t BMI160_CHIP_ID = 0xD1;
static const uint8_t BMI160_REG_MASK = 0x7F; // Register address is 7 bits wide
static const uint8_t BMI160_READ_FLAG = 0x80;
/*
* Register Definitions
*/
// ACC_CONF
static const uint8_t BMI160_ACC_CONF_ACC_US_MASK = 0x1;
static const uint8_t BMI160_ACC_CONF_ACC_US_SHIFT = 7;
static const uint8_t BMI160_ACC_CONF_ACC_BWP_SHIFT = 4;
static const uint8_t BMI160_ACC_CONF_ACC_BWP_MASK = 0x7;
static const uint8_t BMI160_ACC_CONF_ACC_ODR_SHIFT = 0;
static const uint8_t BMI160_ACC_CONF_ACC_ODR_MASK = 0xf;
// Hz = 100 / 2 ^ (8 - ACC_ODR_VAL)
typedef enum { /* value is the interval in microseconds */
BMI160SampleRate_12p5_HZ = 80000,
BMI160SampleRate_25_HZ = 40000,
BMI160SampleRate_50_HZ = 20000,
BMI160SampleRate_100_HZ = 10000,
BMI160SampleRate_200_HZ = 5000,
BMI160SampleRate_400_HZ = 2500,
BMI160SampleRate_800_HZ = 1250,
BMI160SampleRate_1600_HZ = 625,
} BMI160SampleRate;
typedef enum { /* value matches ACC_CONF ODR setting that must be programmed */
BMI160AccODR_12p5_HZ = 5,
BMI160AccODR_25_HZ = 6,
BMI160AccODR_50_HZ = 7,
BMI160AccODR_100_HZ = 8,
BMI160AccODR_200_HZ = 9,
BMI160AccODR_400_HZ = 10,
BMI160AccODR_800_HZ = 11,
BMI160AccODR_1600_HZ = 12,
} BMI160AccODR;
// TODO: Create a better way to change the frequency
#define BMI160_ACC_CONF_ODR_RESET_VALUE_US BMI160SampleRate_100_HZ
#define BMI160_ACC_CONF_NORMAL_BODE_US_AND_BWP 0x2
#define BMI160_DEFAULT_ACC_CONF_VALUE \
((BMI160_ACC_CONF_NORMAL_BODE_US_AND_BWP << BMI160_ACC_CONF_ACC_BWP_SHIFT) | \
(BMI160AccODR_50_HZ << BMI160_ACC_CONF_ACC_ODR_SHIFT))
#define BMI160_ACC_CONF_SELF_TEST_VALUE 0x2c // See 2.8.1 of bmi160 data sheet
// Values for BMI160_REG_ACC_RANGE
static const uint8_t BMI160_ACC_RANGE_2G = 0x3;
static const uint8_t BMI160_ACC_RANGE_4G = 0x5;
static const uint8_t BMI160_ACC_RANGE_8G = 0x8;
static const uint8_t BMI160_ACC_RANGE_16G = 0xC;
// STATUS
static const uint8_t BMI160_STATUS_DRDY_ACC_MASK = (1 << 7);
static const uint8_t BMI160_STATUS_DRDY_GYR_MASK = (1 << 6);
static const uint8_t BMI160_STATUS_DRDY_MAG_MASK = (1 << 5);
static const uint8_t BMI160_STATUS_NVM_RDY_MASK = (1 << 4);
static const uint8_t BMI160_STATUS_FOC_RDY_MASK = (1 << 3);
static const uint8_t BMI160_STATUS_MAG_MAN_OP_MASK = (1 << 2);
static const uint8_t BMI160_STATUS_GYR_SELF_TEST_OK_MASK = (1 << 1);
static const uint8_t BMI160_STATUS_GYR_POR_DETECTED_MASK = (1 << 0);
// INT_TAP[0]
static const uint8_t BMI160_INT_TAP_QUIET_SHIFT = 7;
static const uint8_t BMI160_INT_TAP_SHOCK_SHIFT = 6;
// bits 5:3 reserved
static const uint8_t BMI160_INT_TAP_DUR_SHIFT = 0;
// INT_TAP[1] Register Definition
// bit 7 reserved
static const uint8_t BMI160_INT_TAP_THRESH_SHIFT = 4;
// INT_MAP[0] Register
static const uint8_t BMI160_INT_MAP_FLAT_EN_MASK = (1 << 7);
static const uint8_t BMI160_INT_MAP_ORIENTATION_EN_MASK = (1 << 6);
static const uint8_t BMI160_INT_MAP_SINGLE_TAP_EN_MASK = (1 << 5);
static const uint8_t BMI160_INT_MAP_DOUBLE_TAP_EN_MASK = (1 << 4);
static const uint8_t BMI160_INT_MAP_NO_MOTION_EN_MASK = (1 << 3);
static const uint8_t BMI160_INT_MAP_ANYMOTION_EN_MASK = (1 << 2);
static const uint8_t BMI160_INT_MAP_HIGHG_EN_MASK = (1 << 1);
static const uint8_t BMI160_INT_MAP_LOWG_MASK = (1 << 0);
// INT_MAP[1] Register
static const uint8_t BMI160_INT_MAP_1_INT1_DATA_READY = (1 << 7);
static const uint8_t BMI160_INT_MAP_1_INT1_FIFO_WATERMARK = (1 << 6);
static const uint8_t BMI160_INT_MAP_1_INT1_FIFO_FULL = (1 << 5);
static const uint8_t BMI160_INT_MAP_1_INT1_PMU_TRIGGER = (1 << 4);
static const uint8_t BMI160_INT_MAP_1_INT2_DATA_READY = (1 << 3);
static const uint8_t BMI160_INT_MAP_1_INT2_FIFO_WATERMARK = (1 << 2);
static const uint8_t BMI160_INT_MAP_1_INT2_FIFO_FULL = (1 << 1);
static const uint8_t BMI160_INT_MAP_1_INT2_PMU_TRIGGER = (1 << 0);
// INT_STATUS[0]
static const uint8_t BMI160_INT_STATUS_0_FLAT_MASK = (1 << 7);
static const uint8_t BMI160_INT_STATUS_0_ORIENT_MASK = (1 << 6);
static const uint8_t BMI160_INT_STATUS_0_S_TAP_MASK = (1 << 5);
static const uint8_t BMI160_INT_STATUS_0_D_TAP_MASK = (1 << 4);
static const uint8_t BMI160_INT_STATUS_0_PMU_TRIGGER_MASK = (1 << 3);
static const uint8_t BMI160_INT_STATUS_0_ANYM_MASK = (1 << 2);
static const uint8_t BMI160_INT_STATUS_0_SIGMOT_MASK = (1 << 1);
static const uint8_t BMI160_INT_STATUS_0_STEP_INT_MASK = (1 << 0);
// INT_STATUS[1]
static const uint8_t BMI160_INT_STATUS_1_NOMO_MASK = (1 << 7);
static const uint8_t BMI160_INT_STATUS_1_FWM_MASK = (1 << 6);
static const uint8_t BMI160_INT_STATUS_1_FFULL_MASK = (1 << 5);
static const uint8_t BMI160_INT_STATUS_1_DRDY_MASK = (1 << 4);
static const uint8_t BMI160_INT_STATUS_1_LOWG_MASK = (1 << 3);
static const uint8_t BMI160_INT_STATUS_1_HIGHG_Z_MASK = (1 << 2);
// bit 1 & 0 reserved
// INT_STATUS[2]
static const uint8_t BMI160_INT_STATUS_2_TAP_SIGN = (1 << 7);
static const uint8_t BMI160_INT_STATUS_2_TAP_FIRST_Z = (1 << 6);
static const uint8_t BMI160_INT_STATUS_2_TAP_FIRST_Y = (1 << 5);
static const uint8_t BMI160_INT_STATUS_2_TAP_FIRST_X = (1 << 4);
static const uint8_t BMI160_INT_STATUS_2_ANYM_SIGN = (1 << 3);
static const uint8_t BMI160_INT_STATUS_2_ANYM_FIRST_Z = (1 << 2);
static const uint8_t BMI160_INT_STATUS_2_ANYM_FIRST_Y = (1 << 1);
static const uint8_t BMI160_INT_STATUS_2_ANYM_FIRST_X = (1 << 0);
// INT_EN[0]
static const uint8_t BMI160_INT_EN_0_FLAT_EN = (1 << 7);
static const uint8_t BMI160_INT_EN_0_ORIENT_EN = (1 << 6);
static const uint8_t BMI160_INT_EN_0_S_TAP_EN = (1 << 5);
static const uint8_t BMI160_INT_EN_0_D_TAP_EN = (1 << 4);
// bit 3 reserved
static const uint8_t BMI160_INT_EN_0_ANYMOTION_Z_EN = (1 << 2);
static const uint8_t BMI160_INT_EN_0_ANYMOTION_Y_EN = (1 << 1);
static const uint8_t BMI160_INT_EN_0_ANYMOTION_X_EN = (1 << 0);
// INT_EN[1]
// bit 7 reserved
static const uint8_t BMI160_INT_EN_1_FWM_EN = (1 << 6);
static const uint8_t BMI160_INT_EN_1_FFUL_EN = (1 << 5);
static const uint8_t BMI160_INT_EN_1_DRDY_EN = (1 << 4);
static const uint8_t BMI160_INT_EN_1_LOW_EN = (1 << 3);
static const uint8_t BMI160_INT_EN_1_HIGHZ_EN = (1 << 2);
static const uint8_t BMI160_INT_EN_1_HIGHY_EN = (1 << 1);
static const uint8_t BMI160_INT_EN_1_HIGHX_EN = (1 << 0);
// FIFO_CONFIG[0]
static const uint8_t BMI160_FIFO_CONFIG_0_FWM_SHIFT = 0;
static const uint8_t BMI160_FIFO_CONFIG_0_FWM_MASK = 0xff;
#define BMI160_FIFO_LEN_BYTES 1024
#define BMI160_FIFO_WM_UNIT_BYTES 4
// FIFO_CONFIG[1]
static const uint8_t BMI160_FIFO_CONFIG_1_GYR_EN = (1 << 7);
static const uint8_t BMI160_FIFO_CONFIG_1_ACC_EN = (1 << 6);
static const uint8_t BMI160_FIFO_CONFIG_1_MAG_EN = (1 << 5);
static const uint8_t BMI160_FIFO_CONFIG_1_HDR_EN = (1 << 4);
static const uint8_t BMI160_FIFO_CONFIG_1_TAG_INT1_EN = (1 << 3);
static const uint8_t BMI160_FIFO_CONFIG_1_TAG_INT2_EN = (1 << 2);
static const uint8_t BMI160_FIFO_CONFIG_1_TIME_EN = (1 << 1);
// bit 0 reserved
// INT_MOTION[0]
static const uint8_t BMI160_INT_MOTION_1_ANYM_DUR_SHIFT = 0;
static const uint8_t BMI160_INT_MOTION_1_ANYM_DUR_MASK = 0x3;
static const uint8_t BMI160_INT_MOTION_1_SLOWM_SHIFT = 2;
static const uint8_t BMI160_INT_MOTION_1_SLOWM_MASK = 0xfc;
// INT_MOTION[1]
static const uint8_t BMI160_INT_MOTION_1_ANYM_THRESH_SHIFT = 0;
static const uint8_t BMI160_INT_MOTION_1_ANYM_THRESH_MASK = 0xff;

View file

@ -0,0 +1,78 @@
/*
* 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 <stdint.h>
#include <stdbool.h>
#include "kernel/util/sleep.h"
#include "drivers/spi.h"
#include "board/board.h"
#include "bmi160_private.h"
#include "bmi160_regs.h"
void bmi160_begin_burst(uint8_t addr) {
spi_ll_slave_acquire(BMI160_SPI);
spi_ll_slave_scs_assert(BMI160_SPI);
spi_ll_slave_read_write(BMI160_SPI, addr);
}
void bmi160_end_burst(void) {
spi_ll_slave_scs_deassert(BMI160_SPI);
spi_ll_slave_release(BMI160_SPI);
}
uint8_t bmi160_read_reg(uint8_t reg) {
uint8_t value;
// Registers are read when the address MSB=1
reg |= BMI160_READ_FLAG;
SPIScatterGather sg_info[2] = {
{.sg_len = 1, .sg_out = &reg, .sg_in = NULL}, // address
{.sg_len = 1, .sg_out = NULL, .sg_in = &value} // 8 bit register read
};
spi_slave_burst_read_write_scatter(BMI160_SPI, sg_info, ARRAY_LENGTH(sg_info));
return value;
}
uint16_t bmi160_read_16bit_reg(uint8_t reg) {
// 16-bit registers are in little-endian format
uint16_t value;
reg |= BMI160_READ_FLAG;
SPIScatterGather sg_info[2] = {
{.sg_len = 1, .sg_out = &reg, .sg_in = NULL}, // address
{.sg_len = 2, .sg_out = NULL, .sg_in = &value} // 16 bit register read
};
spi_slave_burst_read_write_scatter(BMI160_SPI, sg_info, ARRAY_LENGTH(sg_info));
return value;
}
void bmi160_write_reg(uint8_t reg, uint8_t value) {
reg &= BMI160_REG_MASK;
SPIScatterGather sg_info[2] = {
{.sg_len = 1, .sg_out = &reg, .sg_in = NULL}, // address
{.sg_len = 1, .sg_out = &value, .sg_in = NULL} // register write
};
spi_slave_burst_read_write_scatter(BMI160_SPI, sg_info, ARRAY_LENGTH(sg_info));
}
void bmi160_enable_spi_mode(void) {
// The BMI160 needs a rising edge on the SCS pin to switch into SPI mode.
// The datasheet recommends performing a read to register 0x7F (reserved)
// to put the chip into SPI mode.
bmi160_read_reg(0x7f);
psleep(2); // Necessary on cold boots; not sure why
}

View file

@ -0,0 +1,37 @@
/*
* 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/imu.h"
#include "drivers/imu/mag3110/mag3110.h"
#include "drivers/mag.h"
#include "drivers/qemu/qemu_accel.h"
void imu_init(void) {
qemu_accel_init();
#if CAPABILITY_HAS_MAGNETOMETER
mag3110_init();
#endif
}
void imu_power_up(void) {
}
void imu_power_down(void) {
}
bool gyro_run_selftest(void) {
return true;
}

View file

@ -0,0 +1,47 @@
/*
* 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/accel.h"
#include "drivers/imu.h"
#include "drivers/imu/bma255/bma255.h"
void imu_init(void) {
bma255_init();
}
void imu_power_up(void) {
// NYI
}
void imu_power_down(void) {
// NYI
}
#if !TARGET_QEMU
////////////////////////////////////
// Accel
//
////////////////////////////////////
void accel_enable_double_tap_detection(bool on) {
}
bool accel_get_double_tap_detection_enabled(void) {
return false;
}
#endif /* !TARGET_QEMU */

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 "system/logging.h"
#include "drivers/imu/bmi160/bmi160.h"
#include "drivers/mag.h"
#include <inttypes.h>
#include <stdbool.h>
#include <stdio.h>
void imu_init(void) {
bmi160_init();
bmi160_set_accel_power_mode(BMI160_Accel_Mode_Normal);
}
void imu_power_up(void) {
// Unused in snowy as PMIC turns on everything
}
void imu_power_down(void) {
// Unused in snowy as PMIC turns off everything
}
// We don't actually support the mag at all on snowy_evt, as we tried a more complicated
// arrangement where the mag was a slave of the bmi160 chip. We never fully implemented it, and
// as we abandoned that approach there's no point in ever implementing it. Below are a bunch of
// stubs that do nothing on this board.
void mag_use(void) {
}
void mag_start_sampling(void) {
}
void mag_release(void) {
}
MagReadStatus mag_read_data(MagData *data) {
return MagReadCommunicationFail;
}
bool mag_change_sample_rate(MagSampleRate rate) {
return false;
}

View file

@ -0,0 +1,40 @@
/*
* 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/imu/bmi160/bmi160.h"
#include "drivers/imu/mag3110/mag3110.h"
#include "system/logging.h"
#include <inttypes.h>
#include <stdbool.h>
#include <stdio.h>
void imu_init(void) {
bmi160_init();
bmi160_set_accel_power_mode(BMI160_Accel_Mode_Normal);
mag3110_init();
}
void imu_power_up(void) {
// Unused in snowy as PMIC turns on everything
}
void imu_power_down(void) {
// Unused in snowy as PMIC turns off everything
}

View file

@ -0,0 +1,39 @@
/*
* 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 <inttypes.h>
#include <stdbool.h>
#include <stdio.h>
#include "system/logging.h"
#include "drivers/imu/lis3dh/lis3dh.h"
#include "drivers/imu/mag3110/mag3110.h"
void imu_init(void) {
// Init accelerometer
lis3dh_init();
// Init magnetometer
mag3110_init();
}
void imu_power_up(void) {
lis3dh_power_up();
}
void imu_power_down(void) {
lis3dh_power_down();
}

View file

@ -0,0 +1,390 @@
/*
* 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 "lis3dh.h"
#include "registers.h"
#include "drivers/i2c.h"
#include "drivers/legacy/accel.h"
#include "system/logging.h"
#include "util/math.h"
#include "util/size.h"
//! @file accel_config.c
//! procedures for dealing with I2C communication with the accel
struct I2CCommand {
uint8_t register_address;
uint8_t value;
};
//
// Boiler plate functions for talking over i2c
//
static uint8_t prv_read_reg(uint8_t address) {
uint8_t reg;
lis3dh_read(address, 1, &reg);
return (reg);
}
static bool prv_write_reg(uint8_t address, uint8_t value) {
return (lis3dh_write(address, 1, &value));
}
static bool send_i2c_commands(struct I2CCommand* commands, int num_commands) {
for (int i = 0; i < num_commands; ++i) {
bool result = prv_write_reg(commands[i].register_address, commands[i].value);
if (!result) {
return false;
}
}
return true;
}
void lis3dh_enable_fifo(void) {
uint8_t ctrl_reg5 = prv_read_reg(LIS3DH_CTRL_REG5);
ctrl_reg5 |= FIFO_EN;
prv_write_reg(LIS3DH_CTRL_REG5, ctrl_reg5);
}
void lis3dh_disable_fifo(void) {
uint8_t ctrl_reg5 = prv_read_reg(LIS3DH_CTRL_REG5);
ctrl_reg5 &= ~FIFO_EN;
prv_write_reg(LIS3DH_CTRL_REG5, ctrl_reg5);
}
bool lis3dh_is_fifo_enabled(void) {
uint8_t ctrl_reg5 = prv_read_reg(LIS3DH_CTRL_REG5);
return (ctrl_reg5 & FIFO_EN);
}
void lis3dh_disable_click(void) {
uint8_t ctrl_reg3 = prv_read_reg(LIS3DH_CTRL_REG3);
ctrl_reg3 &= ~I1_CLICK;
prv_write_reg(LIS3DH_CTRL_REG3, ctrl_reg3);
}
void lis3dh_enable_click(void) {
uint8_t ctrl_reg3 = prv_read_reg(LIS3DH_CTRL_REG3);
ctrl_reg3 |= I1_CLICK;
prv_write_reg(LIS3DH_CTRL_REG3, ctrl_reg3);
}
//
// Accel config Getter/Setters
//
void lis3dh_set_interrupt_axis(AccelAxisType axis, bool double_click) {
// get the current state of the registers
uint8_t reg_1 = prv_read_reg(LIS3DH_CTRL_REG1);
// clear the axis-enable bits
reg_1 = reg_1 & ~(0x1 | 0x2 | 0x4);
uint8_t click_cfg = 0;
switch (axis) {
case ACCEL_AXIS_X:
reg_1 |= 0x01;
click_cfg = 0x01;
break;
case ACCEL_AXIS_Y:
reg_1 |= 0x02;
click_cfg = 0x04;
break;
case ACCEL_AXIS_Z:
reg_1 |= 0x04;
click_cfg = 0x10;
break;
default:
PBL_LOG(LOG_LEVEL_ERROR, "Unknown axis");
}
if (double_click) {
click_cfg <<= 1;
}
if ((!prv_write_reg(LIS3DH_CTRL_REG1, reg_1))
|| (!prv_write_reg(LIS3DH_CLICK_CFG, click_cfg))) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to write axis selection");
}
}
uint8_t lis3dh_get_click_window() {
return prv_read_reg(LIS3DH_TIME_WINDOW);
}
void lis3dh_set_click_window(uint8_t window) {
if (!prv_write_reg(LIS3DH_TIME_WINDOW, MIN(window, LIS3DH_MAX_CLICK_WINDOW))) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to write click latency");
}
}
uint8_t lis3dh_get_click_latency() {
return prv_read_reg(LIS3DH_TIME_LATENCY);
}
void lis3dh_set_click_latency(uint8_t latency) {
if (!prv_write_reg(LIS3DH_TIME_LATENCY, MIN(latency, LIS3DH_MAX_CLICK_LATENCY))) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to write click latency");
}
}
uint8_t lis3dh_get_interrupt_threshold() {
return prv_read_reg(LIS3DH_CLICK_THS);
}
void lis3dh_set_interrupt_threshold(uint8_t threshold) {
if (!prv_write_reg(LIS3DH_CLICK_THS, MIN(threshold, LIS3DH_MAX_THRESHOLD))) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to set interrupt threshold");
}
}
uint8_t lis3dh_get_interrupt_time_limit() {
return prv_read_reg(LIS3DH_TIME_LIMIT);
}
void lis3dh_set_interrupt_time_limit(uint8_t time_limit) {
if (!prv_write_reg(LIS3DH_TIME_LIMIT, MIN(time_limit, LIS3DH_MAX_TIME_LIMIT))) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to set interrupt time limit");
}
}
bool lis3dh_set_fifo_wtm(uint8_t wtm) {
uint8_t fifo_ctrl_reg = prv_read_reg(LIS3DH_FIFO_CTRL_REG);
fifo_ctrl_reg &= ~THR_MASK;
fifo_ctrl_reg |= (wtm & THR_MASK);
return (prv_write_reg(LIS3DH_FIFO_CTRL_REG, fifo_ctrl_reg));
}
uint8_t lis3dh_get_fifo_wtm(void) {
uint8_t fifo_ctrl_reg = prv_read_reg(LIS3DH_FIFO_CTRL_REG);
return (fifo_ctrl_reg & THR_MASK);
}
AccelSamplingRate accel_get_sampling_rate(void) {
uint8_t odr = ODR_MASK & prv_read_reg(LIS3DH_CTRL_REG1);
if (odr == (ODR2 | ODR0)) {
return (ACCEL_SAMPLING_100HZ);
} else if (odr == ODR2) {
return (ACCEL_SAMPLING_50HZ);
} else if (odr == (ODR1 | ODR0)) {
return (ACCEL_SAMPLING_25HZ);
} else if (odr == (ODR1)) {
return (ACCEL_SAMPLING_10HZ);
} else {
PBL_LOG(LOG_LEVEL_ERROR, "Unrecognized ODR value %d", odr);
return (0);
}
}
bool accel_set_sampling_rate(AccelSamplingRate rate) {
uint8_t odr;
switch (rate) {
case ACCEL_SAMPLING_100HZ:
odr = ODR2 | ODR0;
break;
case ACCEL_SAMPLING_50HZ:
odr = ODR2;
break;
case ACCEL_SAMPLING_25HZ:
odr = ODR1 | ODR0;
break;
case ACCEL_SAMPLING_10HZ:
odr = ODR1;
break;
default:
PBL_LOG(LOG_LEVEL_ERROR, "Unsupported sampling rate %d", rate);
return (false);
}
uint8_t ctrl_reg_1 = prv_read_reg(LIS3DH_CTRL_REG1);
ctrl_reg_1 &= ~ODR_MASK;
ctrl_reg_1 |= (odr & ODR_MASK);
//TODO: fix hack below (enabling axes after lis3dh_power_down)
ctrl_reg_1 |= (Xen | Yen | Zen); //enable x, y and z axis
bool res = prv_write_reg(LIS3DH_CTRL_REG1, ctrl_reg_1);
// Update the click limit based on sampling frequency
uint8_t time_limit = rate * LIS3DH_TIME_LIMIT_MULT / LIS3DH_TIME_LIMIT_DIV;
lis3dh_set_interrupt_time_limit(time_limit);
PBL_LOG(LOG_LEVEL_DEBUG, "setting click time limit to 0x%x",
lis3dh_get_interrupt_time_limit());
// Update click latency
uint8_t time_latency = rate * LIS3DH_TIME_LATENCY_MULT / LIS3DH_TIME_LATENCY_DIV;
lis3dh_set_click_latency(time_latency);
PBL_LOG(LOG_LEVEL_DEBUG, "setting click time latency to 0x%x",
lis3dh_get_click_latency());
// Update click window
uint32_t time_window = rate * LIS3DH_TIME_WINDOW_MULT / LIS3DH_TIME_WINDOW_DIV;
time_window = MIN(time_window, 0xff);
lis3dh_set_click_window(time_window);
PBL_LOG(LOG_LEVEL_DEBUG, "setting click time window to 0x%x",
lis3dh_get_click_window());
return (res);
}
Lis3dhScale accel_get_scale(void) {
uint8_t fs = FS_MASK & prv_read_reg(LIS3DH_CTRL_REG4);
if (fs == (FS0 | FS1)) {
return (LIS3DH_SCALE_16G);
} else if (fs == FS1) {
return (LIS3DH_SCALE_8G);
} else if (fs == FS0) {
return (LIS3DH_SCALE_4G);
} else if (fs == 0) {
return (LIS3DH_SCALE_2G);
} else {
PBL_LOG(LOG_LEVEL_ERROR, "Unrecognized FS value %d", fs);
return (LIS3DH_SCALE_UNKNOWN);
}
}
bool accel_set_scale(Lis3dhScale scale) {
uint8_t fs;
switch (scale) {
case LIS3DH_SCALE_16G:
fs = (FS0 | FS1);
break;
case LIS3DH_SCALE_8G:
fs = FS1;
break;
case LIS3DH_SCALE_4G:
fs = FS0;
break;
case LIS3DH_SCALE_2G:
fs = 0;
break;
default:
PBL_LOG(LOG_LEVEL_ERROR, "Unsupported scale %d", scale);
return (false);
}
uint8_t ctrl_reg_4 = prv_read_reg(LIS3DH_CTRL_REG4);
ctrl_reg_4 &= ~FS_MASK;
ctrl_reg_4 |= (fs & FS_MASK);
bool res = prv_write_reg(LIS3DH_CTRL_REG4, ctrl_reg_4);
lis3dh_set_interrupt_threshold(scale * LIS3DH_THRESHOLD_MULT
/ LIS3DH_THRESHOLD_DIV);
PBL_LOG(LOG_LEVEL_DEBUG, "setting click threshold to 0x%x",
lis3dh_get_interrupt_threshold());
return (res);
}
bool lis3dh_set_fifo_mode(uint8_t mode) {
uint8_t fifo_ctrl_reg = prv_read_reg(LIS3DH_FIFO_CTRL_REG);
fifo_ctrl_reg &= ~MODE_MASK;
fifo_ctrl_reg |= (mode & MODE_MASK);
return (prv_write_reg(LIS3DH_FIFO_CTRL_REG, fifo_ctrl_reg));
}
uint8_t lis3dh_get_fifo_mode(void) {
uint8_t fifo_ctrl_reg = prv_read_reg(LIS3DH_FIFO_CTRL_REG);
return (fifo_ctrl_reg & MODE_MASK);
}
//! Configure the accel to run "Self Test 0". See S3.2.2 of the accel datasheet for more information
bool lis3dh_enter_self_test_mode(SelfTestMode mode) {
uint8_t reg4 = 0x8;
switch (mode) {
case SELF_TEST_MODE_ONE:
reg4 |= 0x2;
break;
case SELF_TEST_MODE_TWO:
reg4 |= (0x2 | 0x4);
break;
default:
break;
}
struct I2CCommand test_mode_config[] = {
{ LIS3DH_CTRL_REG1, 0x9f },
{ LIS3DH_CTRL_REG3, 0x00 },
{ LIS3DH_CTRL_REG4, reg4 }
};
return send_i2c_commands(test_mode_config, ARRAY_LENGTH(test_mode_config));
}
void lis3dh_exit_self_test_mode(void) {
lis3dh_config_set_defaults();
}
//
// Boot-time config
//
//! Ask the accel for a 8-bit value that's programmed into the IC at the
//! factory. Useful as a sanity check to make sure everything came up properly.
bool lis3dh_sanity_check(void) {
uint8_t whoami = prv_read_reg(LIS3DH_WHO_AM_I);
PBL_LOG(LOG_LEVEL_DEBUG, "Read accel whomai byte 0x%x, expecting 0x%x", whoami, LIS3DH_WHOAMI_BYTE);
return (whoami == LIS3DH_WHOAMI_BYTE);
}
bool lis3dh_config_set_defaults() {
// Follow the startup sequence from AN3308
struct I2CCommand accel_init_commands[] = {
{ LIS3DH_CTRL_REG1, (ODR1 | ODR0 | Zen | Yen | Xen) }, // 25MHz, Enable X,Y,Z Axes
{ LIS3DH_CTRL_REG2, 0x00 },
{ LIS3DH_CTRL_REG3, I1_WTM }, // FIFO Watermark on INT1
{ LIS3DH_CTRL_REG4, (BDU | FS0 | HR) }, // Block Read, +/- 4g sensitivity
{ LIS3DH_CTRL_REG6, I2_CLICK }, // Click on INT2
{ LIS3DH_INT1_THS, 0x20 }, // intertial threshold (MAX 0x7f)
{ LIS3DH_INT1_DURATION, 0x10 }, // interrupt duration (units of 1/(update frequency) [See CTRL_REG1])
{ LIS3DH_INT1_CFG, 0x00 }, // no inertial interrupts
// click threshold (MAX 0x7f)
{ LIS3DH_CLICK_THS, LIS3DH_SCALE_4G * LIS3DH_THRESHOLD_MULT
/ LIS3DH_THRESHOLD_DIV },
// click time limit (units of 1/(update frequency) [See CTRL_REG1])
{ LIS3DH_TIME_LIMIT, ACCEL_DEFAULT_SAMPLING_RATE * LIS3DH_TIME_LIMIT_MULT
/ LIS3DH_TIME_LIMIT_DIV},
{ LIS3DH_CLICK_CFG, (XS | YS | ZS) }, // single click detection on the X axis
{ LIS3DH_FIFO_CTRL_REG, MODE_BYPASS | 0x19 }, // BYPASS MODE and 25 samples per interrupt
// time latency, ie "debounce time" after the first of a double click
// (units of 1/(update frequency) [See CTRL_REG1])
{ LIS3DH_TIME_LATENCY, ACCEL_DEFAULT_SAMPLING_RATE * LIS3DH_TIME_LATENCY_MULT
/ LIS3DH_TIME_LATENCY_DIV },
// max time allowed between clicks for a double click (end to start)
// (units of 1/(update frequency) [See CTRL_REG1])
{ LIS3DH_TIME_WINDOW, ACCEL_DEFAULT_SAMPLING_RATE * LIS3DH_TIME_WINDOW_MULT
/ LIS3DH_TIME_WINDOW_DIV}
};
if (!send_i2c_commands(accel_init_commands, ARRAY_LENGTH(accel_init_commands))) {
accel_stop();
PBL_LOG(LOG_LEVEL_WARNING, "Failed to initialize accelerometer");
return false;
}
return true;
}

View file

@ -0,0 +1,657 @@
/*
* 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 "lis3dh.h"
#include "board/board.h"
#include "drivers/exti.h"
#include "drivers/gpio.h"
#include "drivers/i2c.h"
#include "drivers/legacy/accel.h"
#include "drivers/periph_config.h"
#include "drivers/vibe.h"
#include "kernel/events.h"
#include "pebble_errors.h"
#include "registers.h"
#include "services/common/accel_manager.h"
#include "services/common/analytics/analytics.h"
#include "services/common/vibe_pattern.h"
#include "services/imu/units.h"
#include "system/logging.h"
#include "os/mutex.h"
#include "system/passert.h"
#include "util/size.h"
#include "kernel/util/sleep.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#include <mcu.h>
#include <inttypes.h>
#include <stdio.h>
#include <string.h>
#define ACCEL_MAX_IDLE_DELTA 100
// State
static bool s_initialized = false;
static bool s_running = false;
static const Lis3dhScale s_accel_scale = LIS3DH_SCALE_4G;
static PebbleMutex * s_accel_mutex;
static uint64_t s_latest_timestamp;
static uint8_t s_pending_accel_event = false;
static bool s_is_idle = false;
static AccelRawData s_last_analytics_position;
static AccelRawData s_latest_reading;
// Buffer for holding the accel data
static SharedCircularBuffer s_buffer;
static uint8_t s_buffer_storage[50*sizeof(AccelRawData)]; // 400 bytes (~1s of data at 50Hz)
static void lis3dh_IRQ1_handler(bool *should_context_switch);
static void lis3dh_IRQ2_handler(bool *should_context_switch);
static void prv_accel_configure_interrupts(void) {
exti_configure_pin(BOARD_CONFIG_ACCEL.accel_ints[0], ExtiTrigger_Rising, lis3dh_IRQ1_handler);
exti_configure_pin(BOARD_CONFIG_ACCEL.accel_ints[1], ExtiTrigger_Rising, lis3dh_IRQ2_handler);
}
static void disable_accel_interrupts(void) {
for (unsigned int i = 0; i < ARRAY_LENGTH(BOARD_CONFIG_ACCEL.accel_ints); i++) {
exti_disable(BOARD_CONFIG_ACCEL.accel_ints[i]);
}
}
static void enable_accel_interrupts(void) {
for (unsigned int i = 0; i < ARRAY_LENGTH(BOARD_CONFIG_ACCEL.accel_ints); i++) {
exti_enable(BOARD_CONFIG_ACCEL.accel_ints[i]);
}
}
static void clear_accel_interrupts(void) {
for (unsigned int i = 0; i < ARRAY_LENGTH(BOARD_CONFIG_ACCEL.accel_ints); i++) {
EXTI_ClearFlag(BOARD_CONFIG_ACCEL.accel_ints[i].exti_line);
EXTI_ClearITPendingBit(BOARD_CONFIG_ACCEL.accel_ints[i].exti_line);
}
}
static int16_t raw_to_mgs(int16_t raw, Lis3dhScale scale) {
int16_t mgs_per_digit;
switch (scale) {
case LIS3DH_SCALE_2G:
mgs_per_digit = 1;
break;
case LIS3DH_SCALE_4G:
mgs_per_digit = 2;
break;
case LIS3DH_SCALE_8G:
mgs_per_digit = 4;
break;
case LIS3DH_SCALE_16G:
mgs_per_digit = 12;
break;
default:
WTF;
}
// least significant 4 bits need to be removed
return ((raw >> 4) * mgs_per_digit);
}
static int16_t get_axis_data(AccelAxisType axis, uint8_t *raw_data) {
// each sample is 2 bytes for each axis
int offset = 2 * BOARD_CONFIG_ACCEL.accel_config.axes_offsets[axis];
int invert = BOARD_CONFIG_ACCEL.accel_config.axes_inverts[axis];
int16_t raw = (((int16_t)raw_data[offset + 1]) << 8) | raw_data[offset];
int16_t converted = (invert ? -1 : 1) * raw_to_mgs(raw, s_accel_scale);
return (converted);
}
// Simple read register command with no error handling
static bool prv_read_register(uint8_t register_address, uint8_t *result) {
return i2c_read_register(I2C_LIS3DH, register_address, result);
}
// Simple write register command with no error handling
static bool prv_write_register(uint8_t register_address, uint8_t value) {
return i2c_write_register(I2C_LIS3DH, register_address, value);
}
static void prv_clear_fifo(void) {
// Use I2C calls instead of accel wrappers to avoid recursion (reset called from lis3dh_read/accel_write)
uint8_t mode;
if (!prv_read_register(LIS3DH_FIFO_CTRL_REG, &mode)) {
return;
}
if (mode != MODE_BYPASS) {
uint8_t fifo_ctrl_reg = mode & ~MODE_MASK;
fifo_ctrl_reg |= (MODE_BYPASS & MODE_MASK);
if (!prv_write_register(LIS3DH_FIFO_CTRL_REG, fifo_ctrl_reg)) {
return;
}
if (!prv_write_register(LIS3DH_FIFO_CTRL_REG, mode)) {
return;
}
}
}
static void prv_reset(void) {
lis3dh_lock();
if (i2c_bitbang_recovery(I2C_LIS3DH)) {
prv_clear_fifo();
}
lis3dh_unlock();
analytics_inc(ANALYTICS_DEVICE_METRIC_ACCEL_RESET_COUNT, AnalyticsClient_System);
}
bool lis3dh_read(uint8_t register_address, uint8_t read_size, uint8_t *buffer) {
bool running = s_running;
if (!running) {
if (!accel_start()) {
// couldn't start the accel
return (false);
}
}
if (!i2c_read_register_block(I2C_LIS3DH, register_address, read_size, buffer)) {
prv_reset();
return (false);
}
if (!running) {
accel_stop();
}
return (true);
}
bool lis3dh_write(uint8_t address, uint8_t write_size, const uint8_t *buffer) {
bool running = accel_running();
if (!running) {
if (!accel_start()) {
// couldn't start the accel
return (false);
}
}
if (!i2c_write_register_block(I2C_LIS3DH, address, write_size, buffer)) {
prv_reset();
return (false);
}
if (!running) {
accel_stop();
}
return true;
}
AccelRawData s_accel_data;
void accel_get_last_data(AccelRawData* data) {
*data = s_accel_data;
}
void accel_get_data(AccelRawData* data, int num_samples) {
if (!s_running) {
PBL_LOG(LOG_LEVEL_ERROR, "Accel Not Running");
return;
}
// accel output registers have adjacent addresses
// MSB enables address auto-increment
int num_bytes = 6 * num_samples;
// Overflow bit doesn't get cleared until number of samples in fifo goes below
// the watermark. Read an extra item from the fifo and just throw it away.
int read_num_bytes = num_bytes + 6;
uint8_t start_addr = 1 << 7 | LIS3DH_OUT_X_L;
uint8_t buffer[read_num_bytes];
lis3dh_read(start_addr, read_num_bytes, buffer);
for (uint8_t *ptr = buffer; ptr < (buffer + num_bytes); ptr+=6) {
data->x = get_axis_data(ACCEL_AXIS_X, ptr);
data->y = get_axis_data(ACCEL_AXIS_Y, ptr);
data->z = get_axis_data(ACCEL_AXIS_Z, ptr);
s_accel_data = *data;
data++;
}
}
void lis3dh_init(void) {
PBL_ASSERTN(!s_initialized);
lis3dh_init_mutex();
s_initialized = true;
if (!accel_start()) {
s_initialized = false;
return;
}
if (!lis3dh_config_set_defaults()) {
// accel write will call reset if it fails, so just try again
if (!lis3dh_config_set_defaults()) {
s_initialized = false;
return;
}
}
shared_circular_buffer_init(&s_buffer, s_buffer_storage, sizeof(s_buffer_storage));
// Test out the peripheral real quick
if (!lis3dh_sanity_check()) {
s_initialized = false;
return;
}
accel_stop();
prv_accel_configure_interrupts();
}
void lis3dh_power_up(void) {
if (accel_start()) {
uint8_t ctrl_reg1;
if (prv_read_register(LIS3DH_CTRL_REG1, &ctrl_reg1)) {
ctrl_reg1 &= ~LPen;
if (prv_write_register(LIS3DH_CTRL_REG1, ctrl_reg1)) {
// Write successful, low power mode disabled
return;
}
}
}
PBL_LOG(LOG_LEVEL_ERROR, "Failed to exit low power mode");
}
void lis3dh_power_down(void) {
if (accel_start()) {
uint8_t ctrl_reg1;
if (prv_read_register(LIS3DH_CTRL_REG1, &ctrl_reg1)) {
ctrl_reg1 |= LPen;
if (prv_write_register(LIS3DH_CTRL_REG1, ctrl_reg1)) {
// Write successful, low power mode enabled
accel_stop();
return;
}
}
}
PBL_LOG(LOG_LEVEL_ERROR, "Failed to enter low power mode");
}
bool accel_running(void) {
return (s_running);
}
bool accel_start(void) {
if (!s_initialized) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to start accel, not yet initialized");
return false;
}
if (s_running) {
return true; // Already running
}
i2c_use(I2C_LIS3DH);
s_running = true;
return true;
}
void accel_stop(void) {
PBL_ASSERTN(s_initialized);
if (s_running) {
disable_accel_interrupts();
clear_accel_interrupts();
i2c_release(I2C_LIS3DH);
enable_accel_interrupts();
s_running = false;
}
}
void lis3dh_init_mutex(void) {
s_accel_mutex = mutex_create();
}
void lis3dh_lock(void) {
mutex_lock(s_accel_mutex);
}
void lis3dh_unlock(void) {
mutex_unlock(s_accel_mutex);
}
static void prv_handle_tap(void *data) {
IMUCoordinateAxis axis;
int direction;
if (s_running) {
uint8_t click_src;
lis3dh_read(LIS3DH_CLICK_SRC, 1, &click_src);
if (click_src & (1 << BOARD_CONFIG_ACCEL.accel_config.axes_offsets[AXIS_X])) {
axis = AXIS_X;
} else if (click_src & (1 << BOARD_CONFIG_ACCEL.accel_config.axes_offsets[AXIS_Y])) {
axis = AXIS_Y;
} else if (click_src & (1 << BOARD_CONFIG_ACCEL.accel_config.axes_offsets[AXIS_Z])) {
axis = AXIS_Z;
} else {
// something has reset the register, ignore
return;
}
// sign bit is zero if positive, 1 if negative
direction = (click_src & Sign) ? -1 : 1;
} else {
// when no-one has subscribed, we only listen to the x axis
axis = AXIS_X;
// no sign info
direction = 0;
}
PebbleEvent e = {
.type = PEBBLE_ACCEL_SHAKE_EVENT,
.accel_tap = {
.axis = axis,
.direction = direction,
},
};
event_put(&e);
}
static void lis3dh_IRQ2_handler(bool *should_context_switch) {
// vibe sometimes triggers the tap interrupt.
// if vibe is on, we disregard the interrupt
if (vibes_get_vibe_strength() == VIBE_STRENGTH_OFF) {
PebbleEvent e = {
.type = PEBBLE_CALLBACK_EVENT,
.callback = {
.callback = prv_handle_tap,
.data = NULL
}
};
*should_context_switch = event_put_isr(&e);
}
}
void accel_set_running(bool running) {
s_running = running;
}
void accel_set_num_samples(uint8_t num_samples) {
if (num_samples == 0) {
// peek mode, no FIFO
lis3dh_set_fifo_mode(MODE_BYPASS);
lis3dh_disable_fifo();
} else {
lis3dh_set_fifo_wtm(num_samples - 1);
// clear fifo
lis3dh_set_fifo_mode(MODE_BYPASS);
// wait 1 ms
psleep(10);
lis3dh_set_fifo_mode(MODE_STREAM);
lis3dh_enable_fifo();
}
}
static void prv_read_samples(void *data) {
uint8_t src_reg;
lis3dh_read(LIS3DH_FIFO_SRC_REG, 1, &src_reg);
uint8_t num_samples = src_reg & FSS_MASK;
AccelRawData accel_raw_data[num_samples];
if (src_reg & FIFO_OVRN) {
PBL_LOG(LOG_LEVEL_ERROR, "Fifo overrun");
analytics_inc(ANALYTICS_DEVICE_METRIC_ACCEL_FIFO_OVERRUN_COUNT, AnalyticsClient_System);
}
if (src_reg & FIFO_WTM) {
accel_get_data(accel_raw_data, num_samples);
if (num_samples > 0) {
s_latest_reading = accel_raw_data[num_samples-1];
}
lis3dh_lock();
if (s_buffer.clients) {
// Only buffer the data if we have clients that are subscribed.
if (!shared_circular_buffer_write(&s_buffer, (uint8_t *)accel_raw_data, num_samples * sizeof(AccelRawData),
false /*advance_slackers*/)) {
// Buffer is full, one or more clients will get dropped data
// We have one or more clients who fell behind reading out of the buffer. Try again, but this time
// resetting the slowest clients until there is room.
PBL_ASSERTN(shared_circular_buffer_write(&s_buffer, (uint8_t *)accel_raw_data, num_samples * sizeof(AccelRawData),
true /*advance_slackers*/));
}
}
lis3dh_unlock();
}
// Record timestamp of newest data in the queue
time_t time_s;
uint16_t time_ms;
rtc_get_time_ms(&time_s, &time_ms);
s_latest_timestamp = ((uint64_t)time_s) * 1000 + time_ms;
if (num_samples == 0) {
accel_reset_pending_accel_event();
return;
}
accel_manager_dispatch_data();
}
uint64_t accel_get_latest_timestamp(void) {
return s_latest_timestamp;
}
static void lis3dh_IRQ1_handler(bool *should_context_switch) {
// It's possible that this interrupt could be leftover after turning accel off.
if (!s_running) {
return;
}
// Only post a new event if the prior one has been picked up. This prevents us from flooding the KernelMain
// queue
if (!s_pending_accel_event) {
s_pending_accel_event = true;
PebbleEvent e = {
.type = PEBBLE_CALLBACK_EVENT,
.callback = {
.callback = prv_read_samples,
.data = NULL
}
};
*should_context_switch = event_put_isr(&e);
}
}
//! Returns the latest accel reading
void accel_get_latest_reading(AccelRawData *data) {
*data = s_latest_reading;
}
//! Clears the pending accel event boolean. Called by KernelMain once it receives the accel_manager_dispatch_data
//! callback
void accel_reset_pending_accel_event(void) {
s_pending_accel_event = false;
}
//! Adds a consumer to the circular buffer
//! @client which client to add
void accel_add_consumer(SharedCircularBufferClient *client) {
lis3dh_lock();
PBL_ASSERTN(shared_circular_buffer_add_client(&s_buffer, client));
lis3dh_unlock();
}
//! Removes a consumer from the circular buffer
//! @client which client to remove
void accel_remove_consumer(SharedCircularBufferClient *client) {
lis3dh_lock();
shared_circular_buffer_remove_client(&s_buffer, client);
lis3dh_unlock();
}
//! Returns number of samples actually read.
//! @param data The buffer to read the data into
//! @client which client is reading
//! @param max_samples Size of buffer in samples
//! @param subsample_num Subsampling numerator
//! @param subsample_den Subsampling denominator
//! @return The actual number of samples read
uint32_t accel_consume_data(AccelRawData *data, SharedCircularBufferClient *client, uint32_t max_samples,
uint16_t subsample_num, uint16_t subsample_den) {
uint16_t items_read;
PBL_ASSERTN(accel_running());
lis3dh_lock();
{
shared_circular_buffer_subsample_items(&s_buffer, client, sizeof(AccelRawData), max_samples, subsample_num,
subsample_den, (uint8_t *)data, &items_read);
}
lis3dh_unlock();
ACCEL_LOG_DEBUG("%"PRIu16" samples (from %"PRIu32" requested) were read for %p",
items_read, max_samples, client);
return (items_read);
}
int accel_peek(AccelData* data) {
if (!s_running) {
return (-1);
}
// No peeking if we're in FIFO mode.
if (lis3dh_get_fifo_mode() == MODE_STREAM) {
return (-2);
}
accel_get_data((AccelRawData*)data, 1);
return (0);
}
// Compute and return the device's delta position to help determine movement as idle.
static uint32_t prv_compute_delta_pos(AccelRawData *cur_pos, AccelRawData *last_pos) {
return abs(last_pos->x - cur_pos->x) + abs(last_pos->y - cur_pos->y) + abs(last_pos->z - cur_pos->z);
}
// Return true if we are "idle". We check for no movement for at least the last hour (the analytics snapshot
// position is updated once/hour).
bool accel_is_idle(void) {
if (!s_is_idle) {
return false;
}
// It was idle recently, see if it's still idle. Note we are avoiding reading the accel hardwware again here
// to keep this call as lightweight as possible. Instead we are just comparing the last read value with
// the value last captured by analytics (which does so on an hourly heartbeat).
AccelRawData accel_data;
accel_get_last_data((AccelRawData*)&accel_data);
s_is_idle = (prv_compute_delta_pos(&accel_data, &s_last_analytics_position) < ACCEL_MAX_IDLE_DELTA);
return s_is_idle;
}
static bool prv_get_accel_data(AccelRawData *accel_data) {
bool running = accel_running();
if (!running) {
if (!accel_start()) {
return false;
}
}
if (lis3dh_get_fifo_mode() != MODE_STREAM) {
accel_get_data((AccelRawData*)accel_data, 1);
} else {
accel_get_last_data((AccelRawData*)accel_data);
}
if (!running) {
accel_stop();
}
return true;
}
// Analytics Metrics
//////////////////////////////////////////////////////////////////////
void analytics_external_collect_accel_xyz_delta(void) {
AccelRawData accel_data;
if (prv_get_accel_data(&accel_data)) {
uint32_t delta = prv_compute_delta_pos(&accel_data, &s_last_analytics_position);
s_is_idle = (delta < ACCEL_MAX_IDLE_DELTA);
s_last_analytics_position = accel_data;
analytics_set(ANALYTICS_DEVICE_METRIC_ACCEL_XYZ_DELTA, delta, AnalyticsClient_System);
}
}
// Self Test
//////////////////////////////////////////////////////////////////////
bool accel_self_test(void) {
AccelRawData data;
AccelRawData data_st;
if (!accel_start()) {
PBL_LOG(LOG_LEVEL_ERROR, "Self test failed, could not start accel");
return false;
}
psleep(10);
accel_get_data(&data, 1);
lis3dh_enter_self_test_mode(SELF_TEST_MODE_ONE);
// ST recommends sleeping for 1ms after programming the module to
// enter self-test mode; a 100x factor of safety ought to be
// sufficient
psleep(100);
accel_get_data(&data_st, 1);
lis3dh_exit_self_test_mode();
accel_stop();
// [MJZ] I have no idea how to interpret the data coming out of the
// accel's self-test mode. If I could make sense of the
// incomprehensible datasheet, I would be able to check if the accel
// output matches the expected values
return ABS(data_st.x) > ABS(data.x);
}
void accel_set_shake_sensitivity_high(bool sensitivity_high) {
// Configure the threshold level at which the LIS3DH will think motion has occurred
if (sensitivity_high) {
lis3dh_set_interrupt_threshold(
BOARD_CONFIG_ACCEL.accel_config.shake_thresholds[AccelThresholdLow]);
} else {
lis3dh_set_interrupt_threshold(
BOARD_CONFIG_ACCEL.accel_config.shake_thresholds[AccelThresholdHigh]);
}
}

View file

@ -0,0 +1,118 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include "applib/accel_service.h"
static const int16_t LIS3DH_COUNTS_PER_G = 4096;
static const int16_t LIS3DH_SAMPLING_RATE_HZ = 50;
static const int LIS3DH_MIN_VALUE = -32768;
static const int LIS3DH_MAX_VALUE = 32767;
static const uint8_t LIS3DH_WHOAMI_BYTE = 0x33;
// Computing AccelSamplingRate * LIS3DH_TIME_LIMIT_MULT / LIS3DH_TIME_LIMIT_DIV
// yields the correct setting for the TIME_LIMIT register
static const int LIS3DH_TIME_LIMIT_MULT = 2240;
static const int LIS3DH_TIME_LIMIT_DIV = 1000;
// Computing AccelSamplingRate * LIS3DH_TIME_LATENCY_MULT / LIS3DH_TIME_LATENCY_DIV
// yields the correct setting for the TIME_LIMIT register
static const int LIS3DH_TIME_LATENCY_MULT = 1280;
static const int LIS3DH_TIME_LATENCY_DIV = 1000;
// Computing AccelSamplingRate * LIS3DH_TIME_WINDOW_MULT / LIS3DH_TIME_WINDOW_DIV
// yields the correct setting for the TIME_WINDOW register
static const int LIS3DH_TIME_WINDOW_MULT = 5120;
static const int LIS3DH_TIME_WINDOW_DIV = 1000;
// Computing AccelScale * LIS3DH_THRESHOLD_MULT / LIS3DH_THRESHOLD_DIV
// yields the correct setting for the CLICK_THS register
static const int LIS3DH_THRESHOLD_MULT = 24;
static const int LIS3DH_THRESHOLD_DIV = 1;
typedef enum {
SELF_TEST_MODE_OFF,
SELF_TEST_MODE_ONE,
SELF_TEST_MODE_TWO,
SELF_TEST_MODE_COUNT
} SelfTestMode;
//! Valid accelerometer scales, in g's
typedef enum {
LIS3DH_SCALE_UNKNOWN = 0,
LIS3DH_SCALE_16G = 16,
LIS3DH_SCALE_8G = 8,
LIS3DH_SCALE_4G = 4,
LIS3DH_SCALE_2G = 2,
} Lis3dhScale;
void lis3dh_init(void);
void lis3dh_lock(void);
void lis3dh_unlock(void);
void lis3dh_init_mutex(void);
void enable_lis3dh_interrupts(void);
void disable_lis3dh_interrupts(void);
bool lis3dh_sanity_check(void);
// Poke specific registers
void lis3dh_disable_click(void);
void lis3dh_enable_click(void);
void lis3dh_disable_fifo(void);
void lis3dh_enable_fifo(void);
bool lis3dh_is_fifo_enabled(void);
void lis3dh_power_up(void);
void lis3dh_power_down(void);
void lis3dh_set_interrupt_axis(AccelAxisType axis, bool double_click);
uint8_t lis3dh_get_interrupt_threshold();
static const uint8_t LIS3DH_MAX_THRESHOLD = 0x7f;
void lis3dh_set_interrupt_threshold(uint8_t threshold);
uint8_t lis3dh_get_interrupt_time_limit();
static const uint8_t LIS3DH_MAX_TIME_LIMIT = 0x7f;
void lis3dh_set_interrupt_time_limit(uint8_t time_limit);
uint8_t lis3dh_get_click_latency();
static const uint8_t LIS3DH_MAX_CLICK_LATENCY = 0xff;
void lis3dh_set_click_latency(uint8_t latency);
uint8_t lis3dh_get_click_window();
static const uint8_t LIS3DH_MAX_CLICK_WINDOW = 0xff;
void lis3dh_set_click_window(uint8_t window);
bool lis3dh_set_fifo_mode(uint8_t);
uint8_t lis3dh_get_fifo_mode(void);
bool lis3dh_set_fifo_wtm(uint8_t);
uint8_t lis3dh_get_fifo_wtm(void);
bool lis3dh_enter_self_test_mode(SelfTestMode mode);
void lis3dh_exit_self_test_mode(void);
bool lis3dh_self_test(void);
bool lis3dh_config_set_defaults();
bool lis3dh_read(uint8_t address, uint8_t read_size, uint8_t *buffer);
bool lis3dh_write(uint8_t address, uint8_t write_size, const uint8_t *buffer);

View file

@ -0,0 +1,126 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
// 0x00 - 0x06: reserved
static const uint8_t LIS3DH_STATUS_REG_AUX = 0x07;
static const uint8_t LIS3DH_OUT_ADC1_L = 0x08;
static const uint8_t LIS3DH_OUT_ADC1_H = 0x09;
static const uint8_t LIS3DH_OUT_ADC2_L = 0x0a;
static const uint8_t LIS3DH_OUT_ADC2_H = 0x0b;
static const uint8_t LIS3DH_OUT_ADC3_L = 0x0c;
static const uint8_t LIS3DH_OUT_ADC3_H = 0x0d;
static const uint8_t LIS3DH_INT_COUNTER_REG = 0x0e;
static const uint8_t LIS3DH_WHO_AM_I = 0x0f;
// 0x10 - 0x1E: reserved
static const uint8_t LIS3DH_TEMP_CFG_REG = 0x1f;
static const uint8_t LIS3DH_CTRL_REG1 = 0x20;
static const uint8_t LIS3DH_CTRL_REG2 = 0x21;
static const uint8_t LIS3DH_CTRL_REG3 = 0x22;
static const uint8_t LIS3DH_CTRL_REG4 = 0x23;
static const uint8_t LIS3DH_CTRL_REG5 = 0x24;
static const uint8_t LIS3DH_CTRL_REG6 = 0x25;
static const uint8_t LIS3DH_REFERENCE = 0x26;
static const uint8_t LIS3DH_STATUS_REG2 = 0x27;
static const uint8_t LIS3DH_OUT_X_L = 0x28;
static const uint8_t LIS3DH_OUT_X_H = 0x29;
static const uint8_t LIS3DH_OUT_Y_L = 0x2a;
static const uint8_t LIS3DH_OUT_Y_H = 0x2b;
static const uint8_t LIS3DH_OUT_Z_L = 0x2c;
static const uint8_t LIS3DH_OUT_Z_H = 0x2d;
static const uint8_t LIS3DH_FIFO_CTRL_REG = 0x2e;
static const uint8_t LIS3DH_FIFO_SRC_REG = 0x2f;
static const uint8_t LIS3DH_INT1_CFG = 0x30;
static const uint8_t LIS3DH_INT1_SRC = 0x31;
static const uint8_t LIS3DH_INT1_THS = 0x32;
static const uint8_t LIS3DH_INT1_DURATION = 0x33;
// 0x34 - 0x37: reserved
static const uint8_t LIS3DH_CLICK_CFG = 0x38;
static const uint8_t LIS3DH_CLICK_SRC = 0x39;
static const uint8_t LIS3DH_CLICK_THS = 0x3a;
static const uint8_t LIS3DH_TIME_LIMIT = 0x3b;
static const uint8_t LIS3DH_TIME_LATENCY = 0x3c;
static const uint8_t LIS3DH_TIME_WINDOW = 0x3d;
static const uint8_t LIS3DH_ACT_THS = 0x3e;
static const uint8_t LIS3DH_INACT_DUR = 0x3f;
// CTRL_REG1
static const uint8_t ODR3 = (1 << 7);
static const uint8_t ODR2 = (1 << 6);
static const uint8_t ODR1 = (1 << 5);
static const uint8_t ODR0 = (1 << 4);
static const uint8_t ODR_MASK = (0xf0);
static const uint8_t LPen = (1 << 3);
static const uint8_t Zen = (1 << 2);
static const uint8_t Yen = (1 << 1);
static const uint8_t Xen = (1 << 0);
// CTRL_REG3
static const uint8_t I1_CLICK = (1 << 7);
static const uint8_t I1_AOI1 = (1 << 6);
static const uint8_t I1_DTRDY = (1 << 4);
static const uint8_t I1_WTM = (1 << 2);
static const uint8_t I1_OVRN = (1 << 1);
//CTRL_REG4
static const uint8_t BDU = (1 << 7);
static const uint8_t BLE = (1 << 6);
static const uint8_t FS1 = (1 << 5);
static const uint8_t FS0 = (1 << 4);
static const uint8_t HR = (1 << 3);
static const uint8_t ST1 = (1 << 2);
static const uint8_t ST0 = (1 << 1);
static const uint8_t SIM = (1 << 0);
static const uint8_t FS_MASK = 0x30;
//CTRL_REG5
static const uint8_t FIFO_EN = (1 << 6);
//CTRL_REG6
static const uint8_t I2_CLICK = (1 << 7);
// CLICK_CFG
static const uint8_t ZD = (1 << 5);
static const uint8_t ZS = (1 << 4);
static const uint8_t YD = (1 << 3);
static const uint8_t YS = (1 << 2);
static const uint8_t XD = (1 << 1);
static const uint8_t XS = (1 << 0);
// CLICK_SRC
static const uint8_t IA = 1 << 6;
static const uint8_t DCLICK = 1 << 5;
static const uint8_t SCLICK = 1 << 4;
static const uint8_t Sign = 1 << 3;
static const uint8_t ZClick = 1 << 2;
static const uint8_t YClick = 1 << 1;
static const uint8_t XClick = 1 << 0;
// FIFO_CTRL_REG
static const uint8_t MODE_BYPASS = 0x0;
static const uint8_t MODE_FIFO = (0x1 << 6);
static const uint8_t MODE_STREAM = (0x1 << 7);
static const uint8_t MODE_MASK = 0xc0;
static const uint8_t THR_MASK = 0x1f;
// FIFO_SRC_REG
static const uint8_t FIFO_WTM = (0x1 << 7);
static const uint8_t FIFO_OVRN = (0x1 << 6);
static const uint8_t FIFO_EMPTY = (0x1 << 5);
static const uint8_t FSS_MASK = 0x1f;

View file

@ -0,0 +1,269 @@
/*
* 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 "mag3110.h"
#include "board/board.h"
#include "console/prompt.h"
#include "drivers/exti.h"
#include "drivers/gpio.h"
#include "drivers/i2c.h"
#include "drivers/mag.h"
#include "drivers/periph_config.h"
#include "kernel/events.h"
#include "system/logging.h"
#include "os/mutex.h"
#include "system/passert.h"
#include "kernel/util/sleep.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#include <inttypes.h>
#include <stdint.h>
static PebbleMutex *s_mag_mutex;
static bool s_initialized = false;
static int s_use_refcount = 0;
// MAG3110 Register Address Map
#define DR_STATUS_REG 0x00
#define OUT_X_MSB_REG 0x01 // a 6-byte read here will return X, Y, Z data
#define WHO_AM_I_REG 0x07
#define SYSMOD_REG 0x08
#define CTRL_REG1 0x10
#define CTRL_REG2 0x11
static bool mag3110_read(uint8_t reg_addr, uint8_t data_len, uint8_t *data) {
return i2c_read_register_block(I2C_MAG3110, reg_addr, data_len, data);
}
static bool mag3110_write(uint8_t reg_addr, uint8_t data) {
return i2c_write_register_block(I2C_MAG3110, reg_addr, 1, &data);
}
static void mag3110_interrupt_handler(bool *should_context_switch) {
if (s_use_refcount == 0) {
// Spurious interrupt firing after we've already turned off the mag. Just ignore.
return;
}
// TODO: May want to use a timer, lowers worst case latency
PebbleEvent e = {
.type = PEBBLE_ECOMPASS_SERVICE_EVENT,
};
*should_context_switch = event_put_isr(&e);
}
//! Move the mag into standby mode, which is a low power mode where we're not actively sampling
//! the sensor or firing interrupts.
static bool prv_enter_standby_mode(void) {
// Ask to enter standby mode
if (!mag3110_write(CTRL_REG1, 0x00)) {
return false;
}
// Wait for the sysmod register to read that we're now in standby mode. This can take up to
// 1/ODR to respond. Since we only support speeds as slow as 5Hz, that means we may be waiting
// for up to 200ms for this part to become ready.
const int NUM_ATTEMPTS = 300; // 200ms + some padding for safety
for (int i = 0; i < NUM_ATTEMPTS; ++i) {
uint8_t sysmod = 0;
if (!mag3110_read(SYSMOD_REG, 1, &sysmod)) {
return false;
}
if (sysmod == 0) {
// We're done and we're now in standby!
return true;
}
// Wait at least 1ms before asking again
psleep(2);
}
return false;
}
// Ask the compass for a 8-bit value that's programmed into the IC at the
// factory. Useful as a sanity check to make sure everything came up properly.
bool mag3110_check_whoami(void) {
static const uint8_t COMPASS_WHOAMI_BYTE = 0xc4;
uint8_t whoami = 0;
mag_use();
mag3110_read(WHO_AM_I_REG, 1, &whoami);
mag_release();
PBL_LOG(LOG_LEVEL_DEBUG, "Read compass whoami byte 0x%x, expecting 0x%x",
whoami, COMPASS_WHOAMI_BYTE);
return (whoami == COMPASS_WHOAMI_BYTE);
}
void mag3110_init(void) {
if (s_initialized) {
return;
}
s_mag_mutex = mutex_create();
s_initialized = true;
if (!mag3110_check_whoami()) {
PBL_LOG(LOG_LEVEL_WARNING, "Failed to query Mag");
}
gpio_input_init(&BOARD_CONFIG_MAG.mag_int_gpio);
exti_configure_pin(BOARD_CONFIG_MAG.mag_int, ExtiTrigger_Rising, mag3110_interrupt_handler);
}
void mag_use(void) {
PBL_ASSERTN(s_initialized);
mutex_lock(s_mag_mutex);
if (s_use_refcount == 0) {
i2c_use(I2C_MAG3110);
exti_enable(BOARD_CONFIG_MAG.mag_int);
}
++s_use_refcount;
mutex_unlock(s_mag_mutex);
}
void mag_release(void) {
PBL_ASSERTN(s_initialized && s_use_refcount != 0);
mutex_lock(s_mag_mutex);
--s_use_refcount;
if (s_use_refcount == 0) {
// We need to put the magnetometer into standby mode and read the data register to reset
// the state so it's ready for next time.
prv_enter_standby_mode();
uint8_t raw_data[7];
// DR_STATUS_REG is immediately before data registers
mag3110_read(DR_STATUS_REG, sizeof(raw_data), raw_data);
// Now we can actually remove power and disable the interrupt
i2c_release(I2C_MAG3110);
exti_disable(BOARD_CONFIG_MAG.mag_int);
}
mutex_unlock(s_mag_mutex);
}
// aligns magnetometer data with the coordinate system we have adopted
// for the watch
static int16_t align_coord_system(int axis, uint8_t *raw_data) {
int offset = 2 * BOARD_CONFIG_MAG.mag_config.axes_offsets[axis];
bool do_invert = BOARD_CONFIG_MAG.mag_config.axes_inverts[axis];
int16_t mag_field_strength = ((raw_data[offset] << 8) | raw_data[offset + 1]);
mag_field_strength *= (do_invert ? -1 : 1);
return (mag_field_strength);
}
// callers responsibility to know if there is valid data to be read
MagReadStatus mag_read_data(MagData *data) {
mutex_lock(s_mag_mutex);
if (s_use_refcount == 0) {
mutex_unlock(s_mag_mutex);
return (MagReadMagOff);
}
MagReadStatus rv = MagReadSuccess;
uint8_t raw_data[7];
// DR_STATUS_REG is immediately before data registers
if (!mag3110_read(DR_STATUS_REG, sizeof(raw_data), raw_data)) {
rv = MagReadCommunicationFail;
goto done;
}
// TODO: shouldn't happen at low sample rate, but handle case where some data
// is overwritten
if ((raw_data[0] & 0xf0) != 0) {
PBL_LOG(LOG_LEVEL_INFO, "Some Mag Sample Data was overwritten, "
"dr_status=0x%x", raw_data[0]);
rv = MagReadClobbered; // we still need to read the data to clear the int
}
// map raw data to watch coord system
data->x = align_coord_system(0, &raw_data[1]);
data->y = align_coord_system(1, &raw_data[1]);
data->z = align_coord_system(2, &raw_data[1]);
done:
mutex_unlock(s_mag_mutex);
return (rv);
}
bool mag_change_sample_rate(MagSampleRate rate) {
mutex_lock(s_mag_mutex);
if (s_use_refcount == 0) {
mutex_unlock(s_mag_mutex);
return (true);
}
bool success = false;
// Enter standby state since we can only change sample rate in this mode.
if (!prv_enter_standby_mode()) {
goto done;
}
// See Table 25 in the data sheet for these values for the CTRL_REG1 register. We leave the
// oversampling values at zero and just set the data rate bits.
uint8_t new_sample_rate_value = 0;
switch(rate) {
case MagSampleRate20Hz:
new_sample_rate_value = 0x1 << 6;
break;
case MagSampleRate5Hz:
new_sample_rate_value = 0x2 << 6;
break;
}
// Write the new sample rate as well as set the bottom bit of the ctrl register to put us into
// active mode.
if (!mag3110_write(CTRL_REG1, new_sample_rate_value | 0x01)) {
goto done;
}
success = true;
done:
mutex_unlock(s_mag_mutex);
return (success);
}
void mag_start_sampling(void) {
mag_use();
// enable automatic magnetic sensor reset & RAW mode
mag3110_write(CTRL_REG2, 0xA0);
mag_change_sample_rate(MagSampleRate5Hz);
}

View file

@ -0,0 +1,20 @@
/*
* 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.
*/
#pragma once
void mag3110_init(void);

View file

@ -0,0 +1,40 @@
/*
* 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.
*/
// Null Magnetometer Driver
#if CAPABILITY_HAS_MAGNETOMETER
#error This driver is only intended for boards without a magnetometer
#endif
#include "drivers/mag.h"
void mag_use(void) {
}
void mag_start_sampling(void) {
}
void mag_release(void) {
}
MagReadStatus mag_read_data(MagData *data) {
return MagReadNoMag;
}
bool mag_change_sample_rate(MagSampleRate rate) {
return false;
}

View file

@ -0,0 +1,185 @@
/*
* 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/led_controller.h"
#include "board/board.h"
#include "drivers/gpio.h"
#include "drivers/i2c.h"
#include "drivers/periph_config.h"
#include "system/logging.h"
#include "system/passert.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#include <mcu.h>
enum {
RegShutdown = 0x00,
RegLedCtrl = 0x01,
RegConfig1 = 0x03,
RegConfig2 = 0x04,
RegRampingMode = 0x05,
RegBreathingMark = 0x06,
RegPwmOut1 = 0x07,
RegPwmOut2 = 0x08,
RegPwmOut3 = 0x09,
RegPwmOut4 = 0x0a,
RegPwmOut5 = 0x0b,
RegPwmOut6 = 0x0c,
RegDataUpdate = 0x10,
RegT0Out1 = 0x11,
RegT0Out2 = 0x12,
RegT0Out3 = 0x13,
RegT0Out4 = 0x14,
RegT0Out5 = 0x15,
RegT0Out6 = 0x16,
RegT1T3Rgb1 = 0x1a,
RegT1T3Rgb2 = 0x1b,
RegT4Out1 = 0x1d,
RegT4Out2 = 0x1e,
RegT4Out3 = 0x1f,
RegT4Out4 = 0x20,
RegT4Out5 = 0x21,
RegT4Out6 = 0x22,
RegTimeUpdate = 0x26,
RegReset = 0xff
};
static bool s_backlight_off;
static bool s_initialized = false;
static uint32_t s_rgb_current_color = LED_BLACK;
static bool write_register(uint8_t register_address, uint8_t value) {
return i2c_write_register(I2C_LED, register_address, value);
}
// used to bring hardware shutdown pin on led controller low, this brings down our shutdown current
static void prv_shutdown(bool shutdown) {
periph_config_acquire_lock();
gpio_output_set(&BOARD_CONFIG_BACKLIGHT.ctl, !shutdown);
periph_config_release_lock();
}
static void prv_init_pins(void) {
periph_config_acquire_lock();
gpio_output_init(&BOARD_CONFIG_BACKLIGHT.ctl, GPIO_OType_PP, GPIO_Speed_2MHz);
gpio_output_set(&BOARD_CONFIG_BACKLIGHT.ctl, false);
periph_config_release_lock();
}
void led_controller_init(void) {
PBL_ASSERTN(BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_IssiI2C);
prv_init_pins();
prv_shutdown(false);
i2c_use(I2C_LED);
// reset the LED controller
if (!write_register(RegReset, 0xaa)) {
PBL_LOG(LOG_LEVEL_ERROR, "LED Controller is MIA");
goto cleanup;
} else {
s_initialized = true;
}
// take the led controller out of shutdown
write_register(RegShutdown, 0x01);
// set config1 to 0x00 (PWM, Audio disable, AGC enable, AGC fast mode)
write_register(RegConfig1, 0x00);
// set config2 to 0x40 (master control, 25mA drive, 0dB gain)
write_register(RegConfig2, 0x70);
// set ramping_mode to 0x00 (disable ramping)
// TODO: this is potentially quite useful for us
write_register(RegRampingMode, 0x00);
// set breathing mark to 0x00 (disable breathing)
// TODO: this is potentially quite useful for us for the RGB LEDs
write_register(RegBreathingMark, 0x00);
s_backlight_off = true;
s_rgb_current_color = LED_BLACK;
cleanup:
i2c_release(I2C_LED);
prv_shutdown(true);
}
void led_controller_backlight_set_brightness(uint8_t brightness) {
if ((BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_IssiI2C) == 0 || !s_initialized) {
return;
}
prv_shutdown(false);
i2c_use(I2C_LED);
write_register(RegPwmOut1, brightness);
write_register(RegPwmOut2, brightness);
write_register(RegPwmOut3, brightness);
write_register(RegDataUpdate, 0xaa);
i2c_release(I2C_LED);
s_backlight_off = (brightness == 0);
if (s_backlight_off && s_rgb_current_color == LED_BLACK) {
prv_shutdown(true);
}
}
void led_controller_rgb_set_color(uint32_t rgb_color) {
if ((BOARD_CONFIG_BACKLIGHT.options & ActuatorOptions_IssiI2C) == 0 || !s_initialized) {
return;
}
s_rgb_current_color = rgb_color;
uint8_t red = (s_rgb_current_color & 0x00FF0000) >> 16;
uint8_t green = (s_rgb_current_color & 0x0000FF00) >> 8;
uint8_t blue = (s_rgb_current_color & 0x000000FF);
prv_shutdown(false);
i2c_use(I2C_LED);
write_register(RegPwmOut4, red);
write_register(RegPwmOut6, blue);
write_register(RegPwmOut5, green);
write_register(RegDataUpdate, 0xaa);
i2c_release(I2C_LED);
if (s_backlight_off && s_rgb_current_color == LED_BLACK) {
prv_shutdown(true);
}
}
uint32_t led_controller_rgb_get_color(void) {
return s_rgb_current_color;
}
void command_rgb_set_color(const char* color) {
uint32_t color_val = strtol(color, NULL, 16);
led_controller_rgb_set_color(color_val);
}

View file

@ -0,0 +1,40 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
//! FIXME: These colors are not gamma-corrected, so will not match normal
//! RGB color values, 100 is max brightness
#define LED_BLACK 0x00000000
#define LED_RED 0x00640000
#define LED_GREEN 0x00006400
#define LED_BLUE 0x00000064
#define LED_ORANGE 0x00285F00
#define LED_DIM_GREEN 0x00003C00 // Low power version for charging indicator
#define LED_DIM_ORANGE 0x000F2300 // Low power version for charging indicator
void led_controller_init(void);
// Not sure these are the correct functions to define atm, but it is fine as a first pass
void led_controller_backlight_set_brightness(uint8_t brightness);
void led_controller_rgb_set_color(uint32_t rgb_color);
uint32_t led_controller_rgb_get_color(void);

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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include <time.h>
#include "applib/accel_service.h"
#include "util/shared_circular_buffer.h"
bool accel_start(void);
void accel_stop(void);
bool accel_running(void);
AccelSamplingRate accel_get_sampling_rate(void);
bool accel_set_sampling_rate(AccelSamplingRate);
void accel_reset_pending_accel_event(void);
uint64_t accel_get_latest_timestamp(void);
void accel_get_latest_reading(AccelRawData *data);
void accel_add_consumer(SharedCircularBufferClient *client);
void accel_remove_consumer(SharedCircularBufferClient *client);
uint32_t accel_consume_data(AccelRawData *data, SharedCircularBufferClient *client,
uint32_t max_samples, uint16_t subsample_num, uint16_t subsample_den);
//! @return result, negative means failure and 0 means pass. See implementation for details
int accel_peek(AccelData *data);
void accel_set_running(bool running);
void accel_set_num_samples(uint8_t num_samples);
// This call is designed to be as lightweight as possible and does not access the hardware.
// Instead, it looks at the last values read from the hardware during normal usage.
bool accel_is_idle(void);
bool accel_update_and_check_is_stationary(void);
extern void accel_manager_dispatch_data(void);
//! The accelerometer supports a changeable sensitivity for shake detection. This call will
//! select whether we want the accelerometer to enter a highly sensitive state with a low
//! threshold, where any minor amount of motion would trigger the system tap event.
//! Note: Setting this value does not ensure that tap detection is enabled.
void accel_set_shake_sensitivity_high(bool sensitivity_high);

63
src/fw/drivers/mag.h Normal file
View file

@ -0,0 +1,63 @@
/*
* 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.
*/
#pragma once
#include "util/attributes.h"
#include <stdbool.h>
#include <stdint.h>
//! @internal
//! Structure containing 3-axis magnetometer data
typedef struct PACKED {
//! magnetic field along the x axis
int16_t x;
//! magnetic field along the y axis
int16_t y;
//! magnetic field along the z axis
int16_t z;
} MagData;
typedef enum {
MagReadSuccess = 0,
MagReadClobbered = -1,
MagReadCommunicationFail = -2,
MagReadMagOff = -3,
MagReadNoMag = -4,
} MagReadStatus;
typedef enum {
MagSampleRate20Hz,
MagSampleRate5Hz
} MagSampleRate;
//! Enable the mag hardware and increment the refcount. Must be matched with a call to
//! mag_release.
void mag_use(void);
//! Enable the mag hardware, configure it in sampling mode and increment the refcount. Must be
//! matched with a call to mag_release.
void mag_start_sampling(void);
//! Release the mag hardware and decrement the refcount. This will turn off the hardware if no one
//! else is still using it (the refcount is still non-zero).
void mag_release(void);
MagReadStatus mag_read_data(MagData *data);
bool mag_change_sample_rate(MagSampleRate rate);

24
src/fw/drivers/mcu.h Normal file
View file

@ -0,0 +1,24 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
//! @return a 96-bit serial number for the MCU, programmed by the MCU manufacturer.
const uint32_t* mcu_get_serial(void);
uint32_t mcu_cycles_to_milliseconds(uint64_t cpu_ticks);

View file

@ -0,0 +1,36 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
typedef struct McuRebootReason {
union {
struct {
bool brown_out_reset:1;
bool pin_reset:1;
bool power_on_reset:1;
bool software_reset:1;
bool independent_watchdog_reset:1;
bool window_watchdog_reset:1;
bool low_power_manager_reset:1;
uint8_t reserved:1;
};
uint8_t reset_mask;
};
} McuRebootReason;

49
src/fw/drivers/mic.h Normal file
View file

@ -0,0 +1,49 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
#include <stddef.h>
#include <stdbool.h>
#define MIC_SAMPLE_RATE (16000) //!< Microphone audio data sample rate
#define MIC_DEFAULT_VOLUME (-1)
typedef const struct MicDevice MicDevice;
//! Microphone audio data handler callback. Called when buffer is full
typedef void (*MicDataHandlerCB)(int16_t *samples, size_t sample_count, void *context);
//! Initialize microphone driver. Should be called on boot
void mic_init(MicDevice *this);
//! Set the mic volume. This must be called afer mic_init, and not while the mic is running.
void mic_set_volume(MicDevice *this, uint16_t volume);
//! Start the microphone. The driver will fill the specified buffer with up to the specified size
//! each time it calls the audio data handler callback. audio_buffer_len should be specified as the
//! length of the buffer (number of 16-bit samples it can hold)
//! @return true if mic was started, false if mic was already running
bool mic_start(MicDevice *this, MicDataHandlerCB data_handler, void *context,
int16_t *audio_buffer, size_t audio_buffer_len);
//! Stop the microphone. If buffer is not full, the remaining samples will be abandoned. No more
//! callbacks will be executed nor data copied into the buffer after this returns
void mic_stop(MicDevice *this);
//! Indicates whether the mic is running
bool mic_is_running(MicDevice *this);

View file

@ -0,0 +1,183 @@
/*
* 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 "board/board.h"
#include "drivers/mic.h"
#include "drivers/accessory.h"
#include "kernel/events.h"
#include "kernel/pbl_malloc.h"
#if RECOVERY_FW
#include "services/prf/accessory/accessory_manager.h"
#else
#include "services/normal/accessory/accessory_manager.h"
#endif
#include "system/logging.h"
#include "system/passert.h"
#include "util/circular_buffer.h"
#include "util/legacy_checksum.h"
#include "system/profiler.h"
static int s_timeout = 0;
static bool s_is_8_bit;
static bool s_is_8khz;
static TimerID s_start_timer;
static int16_t *s_test_buffer;
static void prv_put_byte(uint8_t datum) {
accessory_send_data(&datum, 1);
}
static const uint8_t HDLC_START = 0x7E;
static const uint8_t HDLC_ESCAPE = 0x7D;
static const uint8_t HDLC_ESCAPE_MASK = 0x20;
static void prv_put_hdlc_frame_delimiter(void) {
prv_put_byte(HDLC_START);
}
static void prv_put_byte_hdlc(uint8_t datum) {
if ((datum == HDLC_ESCAPE) || (datum == HDLC_START)) {
prv_put_byte(HDLC_ESCAPE);
prv_put_byte(datum ^ HDLC_ESCAPE_MASK);
} else {
prv_put_byte(datum);
}
}
static void prv_prompt_output_cb(int16_t *samples, size_t sample_count, void *context) {
const int OUTPUT_SAMPLE_RATE = (s_is_8khz) ? 8000 : 16000;
int to_process = MIN((int)sample_count, s_timeout);
s_timeout -= to_process;
if (to_process > 0) {
// Groups of samples are encapsulated in HDLC-like framing in order to verify the integrity of
// samples
prv_put_hdlc_frame_delimiter();
int num_bytes = (to_process * (s_is_8_bit ? 1 : 2)) / (MIC_SAMPLE_RATE/OUTPUT_SAMPLE_RATE);
// Store frame in temporary buffer in order to calculate CRC after subsample and/or bit-width
// conversion
uint8_t buf[num_bytes];
int buf_idx = 0;
uint8_t *d = (uint8_t *)samples;
// Subsample by skipping every second sample if output rate is set to 8kHz
for (int i = 0; i < to_process * 2; i += 2 * (MIC_SAMPLE_RATE/OUTPUT_SAMPLE_RATE)) {
if (s_is_8_bit) {
// Convert 16-bit PCM representation to 8-bit PCM representation
uint8_t b = d[i + 1] ^ 0x80;
buf[buf_idx++] = b;
prv_put_byte_hdlc(b);
} else {
buf[buf_idx++] = d[i];
prv_put_byte_hdlc(d[i]);
buf[buf_idx++] = d[i + 1];
prv_put_byte_hdlc(d[i + 1]);
}
}
uint32_t crc = legacy_defective_checksum_memory(buf, num_bytes);
prv_put_byte_hdlc((uint8_t) crc);
prv_put_byte_hdlc((uint8_t) (crc >> 8));
prv_put_byte_hdlc((uint8_t) (crc >> 16));
prv_put_byte_hdlc((uint8_t) (crc >> 24));
prv_put_hdlc_frame_delimiter();
}
if (s_timeout == 0) {
mic_stop(MIC);
PROFILER_STOP;
PROFILER_PRINT_STATS;
kernel_free(s_test_buffer);
accessory_enable_input();
#if RECOVERY_FW
const AccessoryInputState input_state = AccessoryInputStateMfg;
#else
const AccessoryInputState input_state = AccessoryInputStateIdle;
#endif
PBL_ASSERTN(accessory_manager_set_state(input_state));
}
}
static void prv_mic_start(void *data) {
const size_t BUFFER_SIZE = 24;
new_timer_delete(s_start_timer);
s_test_buffer = kernel_malloc(BUFFER_SIZE * sizeof(int16_t));
if (!s_test_buffer) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to malloc buffer for 'mic start' command");
return;
}
uint32_t width = s_is_8_bit ? 8 : 16;
uint32_t rate = s_is_8khz ? 8 : 16;
PBL_LOG(LOG_LEVEL_ALWAYS, "Starting mic recording: %"PRIu32"-bit @ %"PRIu32"kHz for %"PRIu32
" samples", width, rate, (s_timeout / (MIC_SAMPLE_RATE / (rate * 1000))));
PROFILER_INIT;
PROFILER_START;
if (!mic_start(MIC, &prv_prompt_output_cb, NULL, s_test_buffer, BUFFER_SIZE)) {
kernel_free(s_test_buffer);
}
}
void command_mic_start(char *timeout_str, char *sample_size_str, char *sample_rate_str,
char *volume_str) {
static const int MAX_TIMEOUT = 60;
if (!accessory_manager_set_state(AccessoryInputStateMic)) {
PBL_LOG(LOG_LEVEL_ERROR, "The accessory is already in use!");
return;
}
s_timeout = strtol(timeout_str, NULL, 10);
if (s_timeout <= 0) {
s_timeout = 1;
} else if (s_timeout > MAX_TIMEOUT) {
s_timeout = MAX_TIMEOUT;
}
int volume = strtol(volume_str, NULL, 10);
mic_set_volume(MIC, MIN(volume, 1024));
s_is_8_bit = strtol(sample_size_str, NULL, 10) == 8; // assume 16 bit if not 8 bit
s_is_8khz = strtol(sample_rate_str, NULL, 10) == 8000; // assume 16kHz if not set to 8000
// Convert timeout in seconds to sample count so that the exact amount of samples are sent
s_timeout *= MIC_SAMPLE_RATE;
// Boost the accessory connector baud rate if necessary
accessory_disable_input();
if ((!s_is_8_bit) && (!s_is_8khz)) {
accessory_set_baudrate(AccessoryBaud460800);
} else if ((!s_is_8_bit) || (!s_is_8khz)) {
accessory_set_baudrate(AccessoryBaud230400);
}
// Start timer after a short delay to allow receiving end to switch baud rate
s_start_timer = new_timer_create();
new_timer_start(s_start_timer, 500, &prv_mic_start, NULL, 0);
}
void command_mic_read() {
command_mic_start("3", "16", "16000", "100");
}

226
src/fw/drivers/mpu.c Normal file
View file

@ -0,0 +1,226 @@
/*
* 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 "mpu.h"
#include "mcu/cache.h"
#include "system/passert.h"
#include "util/size.h"
#include <inttypes.h>
#include "FreeRTOS.h"
#include "task.h"
#include "portmacro.h"
#define CMSIS_COMPATIBLE
#include <mcu.h>
extern const uint32_t __SRAM_size__[];
#if !defined(SRAM_BASE)
// On the STM32F2, SRAM_BASE is not defined, but is equal to SRAM1_BASE
#define SRAM_BASE SRAM1_BASE
#endif
#define SRAM_END (SRAM_BASE + (uint32_t)__SRAM_size__)
typedef struct PermissionMapping {
bool priv_read:1;
bool priv_write:1;
bool user_read:1;
bool user_write:1;
uint8_t value:3;
} PermissionMapping;
static const PermissionMapping s_permission_mappings[] = {
{ false, false, false, false, 0x0 },
{ true, true, false, false, 0x1 },
{ true, true, true, false, 0x2 },
{ true, true, true, true, 0x3 },
{ true, false, false, false, 0x5 },
{ true, false, true, false, 0x6 },
{ true, false, true, false, 0x7 } // Both 0x6 and 0x7 map to the same permissions.
};
static const uint32_t s_cache_settings[MpuCachePolicyNum] = {
[MpuCachePolicy_NotCacheable] = (0x1 << MPU_RASR_TEX_Pos) | (MPU_RASR_S_Msk),
[MpuCachePolicy_WriteThrough] = (MPU_RASR_S_Msk | MPU_RASR_C_Msk),
[MpuCachePolicy_WriteBackWriteAllocate] =
(0x1 << MPU_RASR_TEX_Pos) | (MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk),
[MpuCachePolicy_WriteBackNoWriteAllocate] =
(MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk),
};
static uint8_t get_permission_value(const MpuRegion* region) {
for (unsigned int i = 0; i < ARRAY_LENGTH(s_permission_mappings); ++i) {
if (s_permission_mappings[i].priv_read == region->priv_read &&
s_permission_mappings[i].priv_write == region->priv_write &&
s_permission_mappings[i].user_read == region->user_read &&
s_permission_mappings[i].user_write == region->user_write) {
return s_permission_mappings[i].value;
}
}
WTF;
return 0;
}
static uint8_t get_size_field(const MpuRegion* region) {
unsigned int size = 32;
int result = 4;
while (size != region->size) {
PBL_ASSERT(size < region->size || size == 0x400000, "Invalid region size: %"PRIu32,
region->size);
size *= 2;
++result;
}
return result;
}
void mpu_enable(void) {
MPU->CTRL |= (MPU_CTRL_ENABLE_Msk | MPU_CTRL_PRIVDEFENA_Msk);
}
void mpu_disable(void) {
MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk;
}
// Get the required region base address and region attribute register settings for the given region.
// These are the values which should written to the RBAR and RASR registers to configure that
// region.
void mpu_get_register_settings(const MpuRegion* region, uint32_t *base_address_reg,
uint32_t *attributes_reg) {
PBL_ASSERTN(region);
PBL_ASSERTN((region->base_address & 0x1f) == 0);
PBL_ASSERTN((region->region_num & ~0xf) == 0);
PBL_ASSERTN((region->cache_policy != MpuCachePolicy_Invalid) &&
(region->cache_policy < MpuCachePolicyNum));
// MPU Region Base Address Register
// | Addr (27 bits) | Region Valid Bit | Region Num (4 bits) |
// The address is unshifted, we take the top bits of the address and assume everything below
// is zero, since the address must be power of 2 size aligned.
*base_address_reg = region->base_address |
0x1 << 4 |
region->region_num;
// MPU Region Attribute and Size Register
// A lot of stuff here! Split into bytes...
// | Reserved (3 bits) | XN Bit | Reserved Bit | Permission Field (3 bits) |
// | Reserved (2 bits) | TEX (3 bits) | S | C | B |
// | Subregion Disable Byte |
// | Reserved (2 bits) | Size Field (5 bits) | Enable Bit |
*attributes_reg = (get_permission_value(region) << 24) |
s_cache_settings[region->cache_policy] |
region->disabled_subregions << 8 | // Disabled subregions
(get_size_field(region) << 1) |
region->enabled; // Enabled
}
void mpu_set_region(const MpuRegion* region) {
uint32_t base_reg, attr_reg;
mpu_get_register_settings(region, &base_reg, &attr_reg);
MPU->RBAR = base_reg;
MPU->RASR = attr_reg;
}
MpuRegion mpu_get_region(int region_num) {
MpuRegion region = { .region_num = region_num };
MPU->RNR = region_num;
const uint32_t attributes = MPU->RASR;
region.enabled = attributes & 0x1;
if (region.enabled) {
const uint8_t size_field = (attributes >> 1) & 0x1f;
region.size = 32 << (size_field - 4);
region.disabled_subregions = (attributes & 0x0000ff00) >> 8;
const uint32_t raw_base_address = MPU->RBAR;
region.base_address = raw_base_address & ~(region.size - 1);
const uint8_t access_permissions = (attributes >> 24) & 0x7;
for (unsigned int i = 0; i < ARRAY_LENGTH(s_permission_mappings); ++i) {
if (s_permission_mappings[i].value == access_permissions) {
region.priv_read = s_permission_mappings[i].priv_read;
region.priv_write = s_permission_mappings[i].priv_write;
region.user_read = s_permission_mappings[i].user_read;
region.user_write = s_permission_mappings[i].user_write;
break;
}
}
}
return region;
}
// Fill in the task parameters for a new task with the configurable memory regions we want.
void mpu_set_task_configurable_regions(MemoryRegion_t *memory_regions,
const MpuRegion **region_ptrs) {
unsigned int region_num, region_idx;
uint32_t base_reg, attr_reg;
// Setup the configurable MPU regions
for (region_num=portFIRST_CONFIGURABLE_REGION, region_idx=0; region_num <= portLAST_CONFIGURABLE_REGION;
region_num++, region_idx++) {
const MpuRegion *mpu_region = region_ptrs[region_idx];
MpuRegion unused_region = {};
// If not region defined, use unused
if (mpu_region == NULL) {
mpu_region = &unused_region;
attr_reg = 0; // Has a 0 in the enable bit, so this region won't be enabled.
} else {
// Make sure that the region numbers passed in jive with the configurable region numbers.
PBL_ASSERTN(mpu_region->region_num == region_num);
// Our FreeRTOS port makes the assumption that the ulParameters field contains exactly what
// should be placed into the MPU_RASR register. It will figure out the MPU_RBAR from the
// pvBaseAddress field.
mpu_get_register_settings(mpu_region, &base_reg, &attr_reg);
}
memory_regions[region_idx] = (MemoryRegion_t) {
.pvBaseAddress = (void *)mpu_region->base_address,
.ulLengthInBytes = mpu_region->size,
.ulParameters = attr_reg,
};
}
}
bool mpu_memory_is_cachable(const void *addr) {
if (!dcache_is_enabled()) {
return false;
}
// TODO PBL-37601: We're assuming only SRAM is cachable for now for simplicity sake. We should
// account for MPU configuration and also the fact that memory-mapped QSPI access goes through the
// cache.
return ((uint32_t)addr >= SRAM_BASE) && ((uint32_t)addr < SRAM_END);
}
void mpu_init_region_from_region(MpuRegion *copy, const MpuRegion *from, bool allow_user_access) {
*copy = *from;
copy->user_read = allow_user_access;
copy->user_write = allow_user_access;
}

64
src/fw/drivers/mpu.h Normal file
View file

@ -0,0 +1,64 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include "freertos_types.h"
typedef enum MpuCachePolicy {
MpuCachePolicy_Invalid,
MpuCachePolicy_NotCacheable,
MpuCachePolicy_WriteThrough,
MpuCachePolicy_WriteBackWriteAllocate,
MpuCachePolicy_WriteBackNoWriteAllocate,
MpuCachePolicyNum
} MpuCachePolicy;
typedef struct MpuRegion {
uint8_t region_num:4;
bool enabled:1;
uintptr_t base_address;
uint32_t size;
uint8_t disabled_subregions; // 8 bits, each disables 1/8 of the region.
MpuCachePolicy cache_policy;
bool priv_read:1;
bool priv_write:1;
bool user_read:1;
bool user_write:1;
} MpuRegion;
void mpu_enable(void);
void mpu_disable(void);
void mpu_set_region(const MpuRegion* region);
MpuRegion mpu_get_region(int region_num);
void mpu_get_register_settings(const MpuRegion* region, uint32_t *base_address_reg,
uint32_t *attributes_reg);
void mpu_set_task_configurable_regions(MemoryRegion_t *memory_regions,
const MpuRegion **region_ptrs);
bool mpu_memory_is_cachable(const void *addr);
void mpu_init_region_from_region(MpuRegion *copy, const MpuRegion *from, bool allow_user_access);

72
src/fw/drivers/otp.h Normal file
View file

@ -0,0 +1,72 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
#include <stdbool.h>
#if PLATFORM_TINTIN || PLATFORM_SNOWY || PLATFORM_SPALDING
enum {
// ML/FL / 1.0 and later:
OTP_SERIAL1 = 0,
OTP_HWVER1 = 1,
OTP_PCBA_SERIAL1 = 2,
// Quanta / HW 1.3 and later:
OTP_SERIAL2 = 3,
OTP_SERIAL3 = 4,
OTP_SERIAL4 = 5,
OTP_SERIAL5 = 6,
OTP_PCBA_SERIAL2 = 7,
OTP_PCBA_SERIAL3 = 8,
NUM_OTP_SLOTS = 16,
};
#elif PLATFORM_SILK || PLATFORM_CALCULUS || PLATFORM_ROBERT
enum {
OTP_HWVER1 = 0,
OTP_HWVER2 = 1,
OTP_HWVER3 = 2,
OTP_HWVER4 = 3,
OTP_HWVER5 = 4,
OTP_SERIAL1 = 5,
OTP_SERIAL2 = 6,
OTP_SERIAL3 = 7,
OTP_SERIAL4 = 8,
OTP_SERIAL5 = 9,
OTP_PCBA_SERIAL1 = 10,
OTP_PCBA_SERIAL2 = 11,
OTP_PCBA_SERIAL3 = 12,
NUM_OTP_SLOTS = 16,
};
#else
#error "OTP Slots not set for platform"
#endif
typedef enum {
OtpWriteSuccess = 0,
OtpWriteFailAlreadyWritten = 1,
OtpWriteFailCorrupt = 2,
} OtpWriteResult;
uint8_t * otp_get_lock(const uint8_t index);
bool otp_is_locked(const uint8_t index);
char * otp_get_slot(const uint8_t index);
OtpWriteResult otp_write_slot(const uint8_t index, const char *value);

View file

@ -0,0 +1,25 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
void periph_config_init(void);
void periph_config_acquire_lock(void);
void periph_config_release_lock(void);
void periph_config_enable(void *periph, uint32_t rcc_bit);
void periph_config_disable(void *periph, uint32_t rcc_bit);

68
src/fw/drivers/pmic.h Normal file
View file

@ -0,0 +1,68 @@
/*
* 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.
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
//! Initialize the PMIC driver. Call this once at startup.
bool pmic_init(void);
//! @return The reset reason or 0 if the driver was not able to determine a reset reason
uint32_t pmic_get_last_reset_reason(void);
//! Tell the PMIC to power off the board and enter a standby-like state. All components will
//! have their power removed (except for the RTC so we'll still keep time) and the PMIC itself
//! will monitor the buttons for when to wake up.
bool pmic_power_off(void);
//! Enable the battery monitor portion of the PMIC. Remember to turn this off with
//! pmic_disable_battery_measure when immediate readings aren't required.
bool pmic_enable_battery_measure(void);
//! Disable the battery monitor portion of the PMIC.
bool pmic_disable_battery_measure(void);
//! Enable and disable the charging portion of the PMIC.
bool pmic_set_charger_state(bool enable);
//! @return true if the PMIC thinks we're charging (adding additional charge to the battery).
//! Note that once we hit full charge we'll no longer be charging, which is a different state
//! that pmic_is_usb_connected.
bool pmic_is_charging(void);
//! @return true if a usb-ish charger cable is currently connected.
bool pmic_is_usb_connected(void);
//! Read information about the chip for tracking purposes.
void pmic_read_chip_info(uint8_t *chip_id, uint8_t *chip_revision, uint8_t *buck1_vset);
//! Get a reading for VSYS from the PMIC.
uint16_t pmic_get_vsys(void);
// FIXME: The following functions are unrelated to the PMIC and should be moved to the
// display/accessory connector drivers once we have them.
//! Enables the LDO3 power rail. Used for the MFi/Magnetometer on snowy_bb, MFi on snowy_evt.
void set_ldo3_power_state(bool enabled);
//! Enables the 4.5V power rail. Used for the display on snowy.
void set_4V5_power_state(bool enabled);
//! Enables the 6.6V power rail. Used for the display on snowy.
void set_6V6_power_state(bool enabled);

View file

@ -0,0 +1,526 @@
/*
* 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/pmic.h"
#include "board/board.h"
#include "console/prompt.h"
#include "drivers/battery.h"
#include "drivers/exti.h"
#include "drivers/gpio.h"
#include "drivers/i2c.h"
#include "drivers/periph_config.h"
#include "kernel/events.h"
#include "services/common/system_task.h"
#include "system/logging.h"
#include "system/passert.h"
#include "stm32f4xx_rcc.h"
#include "stm32f4xx_gpio.h"
#include "stm32f4xx_adc.h"
static TimerID s_debounce_charger_timer = TIMER_INVALID_ID;
#define CHARGER_DEBOUNCE_MS 400
//! Remember GPIO output states so we can change the state of individual GPIOs
//! without having to do a read-modify-write.
static uint8_t s_pmic_gpio_output_state = 0;
typedef enum PmicGpio {
PmicGpio1 = (1 << 0),
PmicGpio2 = (1 << 1),
PmicGpio3 = (1 << 2),
PmicGpio4 = (1 << 3),
PmicGpio5 = (1 << 4),
} PmicGpio;
typedef enum {
PmicRegisters_SD1_VOLTAGE = 0x01,
PmicRegisters_LDO1_VOLTAGE = 0x02,
PmicRegisters_LDO2_VOLTAGE = 0x03,
PmicRegisters_GPIO1_CNTL = 0x09,
PmicRegisters_GPIO2_CNTL = 0x0a,
PmicRegisters_GPIO3_CNTL = 0x0b,
PmicRegisters_GPIO4_CNTL = 0x0c,
PmicRegisters_GPIO5_CNTL = 0x0d,
PmicRegisters_GPIO_SIG_OUT = 0x20,
PmicRegisters_GPIO_SIG_IN = 0x21,
PmicRegisters_REG1_VOLTAGE = 0x22,
PmicRegisters_REG2_VOLTAGE = 0x23,
PmicRegisters_REG_CNTL = 0x24,
PmicRegisters_GPIO_CNTL1 = 0x25,
PmicRegisters_GPIO_CNTL2 = 0x26,
PmicRegisters_SD_CNTL1 = 0x30,
PmicRegisters_BATT_VOLTAGE_MON = 0x32,
PmicRegisters_STARTUP_CNTL = 0x33,
PmicRegisters_REFERENCE_CNTL = 0x35,
PmicRegisters_RESET_CNTL = 0x36,
PmicRegisters_OVERTEMP_CNTL = 0x37,
PmicRegisters_REG_STANDBY_MOD1 = 0x39,
PmicRegisters_PWM_CNTL_L = 0x41,
PmicRegisters_PWM_CNTL_H = 0x42,
PmicRegisters_CURR1_VAL = 0x43,
PmicRegisters_CURR2_VAL = 0x44,
PmicRegisters_REG_STATUS = 0x73,
PmicRegisters_INT_MASK_1 = 0x74,
PmicRegisters_INT_MASK_2 = 0x75,
PmicRegisters_INT_STATUS_1 = 0x77,
PmicRegisters_INT_STATUS_2 = 0x78,
PmicRegisters_CHARGE_CNTL = 0x80,
PmicRegisters_CHARGE_VOLTAGE_CNTL = 0x81,
PmicRegisters_CHARGE_CURRENT_CNTL = 0x82,
PmicRegisters_CHARGE_CONFIG_1 = 0x83,
PmicRegisters_CHARGE_CONFIG_2 = 0x84,
PmicRegisters_CHARGE_SUPERVISION = 0x85,
PmicRegisters_CHARGE_STATUS_1 = 0x86,
PmicRegisters_CHARGE_STATUS_2 = 0x87,
PmicRegisters_LOCK_REG = 0x8e,
PmicRegisters_CHIP_ID = 0x90,
PmicRegisters_CHIP_REV = 0x91,
PmicRegisters_FUSE_5 = 0xa5,
PmicRegisters_FUSE_6 = 0xa6,
PmicRegisters_FUSE_7 = 0xa7,
PmicRegisters_FUSE_8 = 0xa8,
PmicRegisters_FUSE_9 = 0xa9,
PmicRegisters_FUSE_10 = 0xaa,
PmicRegisters_FUSE_11 = 0xab,
PmicRegisters_FUSE_12 = 0xac,
PmicRegisters_FUSE_13 = 0xad,
PmicRegisters_FUSE_14 = 0xae,
PmicRegisters_FUSE_15 = 0xaf,
} PmicRegisters;
static const PmicRegisters s_registers[] = {
0x01, 0x02, 0x03, 0x09, 0x0a, 0x0b, 0x0c, 0x0d, 0x20, 0x21,
0x22, 0x23, 0x24, 0x25, 0x26, 0x30, 0x32, 0x33, 0x35, 0x36,
0x37, 0x39, 0x41, 0x42, 0x43, 0x44, 0x73, 0x74, 0x75, 0x77,
0x78, 0x80, 0x81, 0x82, 0x83, 0x84, 0x85, 0x86, 0x87, 0x8e,
0x90, 0x91, 0xa5, 0xa6, 0xa7, 0xa8, 0xa9, 0xaa, 0xab, 0xac,
0xad, 0xae, 0xaf,
};
static bool prv_init_gpio(void) {
periph_config_acquire_lock();
// Init PMIC_INTN
gpio_input_init_pull_up_down(&BOARD_CONFIG_POWER.pmic_int_gpio, GPIO_PuPd_UP);
periph_config_release_lock();
return true;
}
//! Interrupt masks for InterruptStatus1 and InterruptMask1 registers
enum PmicInt1 {
PmicInt1_Trickle = (1 << 0), //!< Trickle charge
PmicInt1_NoBat = (1 << 1), //!< Battery detached
PmicInt1_Resume = (1 << 2), //!< Resuming charge on drop after full
PmicInt1_EOC = (1 << 3), //!< End of charge
PmicInt1_ChDet = (1 << 4), //!< Charger detected
PmicInt1_OnKey = (1 << 5), //!< On Key held
PmicInt1_OvTemp = (1 << 6), //!< Set when 110deg is exceeded
PmicInt1_LowBat = (1 << 7), //!< Low Battery detected. Set when BSUP drops below ResVoltFall
};
enum PmicRail {
PmicRail_SD1, //!< 1.8V
PmicRail_LDO1, //!< 3.0V
PmicRail_LDO2, //!< 2.0V
};
#define AS3701B_CHIP_ID 0x11
static bool prv_read_register(uint8_t register_address, uint8_t *result) {
i2c_use(I2C_AS3701B);
bool rv = i2c_read_register(I2C_AS3701B, register_address, result);
i2c_release(I2C_AS3701B);
return rv;
}
static bool prv_write_register(uint8_t register_address, uint8_t value) {
i2c_use(I2C_AS3701B);
bool rv = i2c_write_register(I2C_AS3701B, register_address, value);
i2c_release(I2C_AS3701B);
return rv;
}
static bool prv_set_register_bit(uint8_t register_address, uint8_t bit, bool enable) {
uint8_t val;
if (!prv_read_register(register_address, &val)) {
return false;
}
if (enable) {
val |= (1 << bit);
} else {
val &= ~(1 << bit);
}
return prv_write_register(register_address, val);
}
static bool prv_set_pmic_gpio_outputs(PmicGpio set_mask, PmicGpio clear_mask) {
PBL_ASSERTN((set_mask & clear_mask) == 0);
uint8_t new_output_state = s_pmic_gpio_output_state;
new_output_state |= set_mask;
new_output_state &= ~clear_mask;
if (prv_write_register(PmicRegisters_GPIO_SIG_OUT, new_output_state)) {
s_pmic_gpio_output_state = new_output_state;
return true;
}
return false;
}
static void prv_init_pmic_gpio_outputs(void) {
// Sync the state of the PMIC GPIO output register with the value that we
// think it has.
if (!prv_set_pmic_gpio_outputs(0, 0)) {
PBL_LOG(LOG_LEVEL_ERROR, "Could not initialize PMIC GPIO outputs");
}
}
static void prv_handle_charge_state_change(void *null) {
const bool is_charging = pmic_is_charging();
const bool is_connected = pmic_is_usb_connected();
PBL_LOG(LOG_LEVEL_DEBUG, "AS3701b Interrupt: Charging? %s Plugged? %s",
is_charging ? "YES" : "NO", is_connected ? "YES" : "NO");
PebbleEvent event = {
.type = PEBBLE_BATTERY_CONNECTION_EVENT,
.battery_connection = {
.is_connected = battery_is_usb_connected(),
},
};
event_put(&event);
}
// Read the interrupt status registers to clear pending bits.
static void prv_clear_pending_interrupts(void) {
uint8_t throwaway_read_result;
prv_read_register(PmicRegisters_INT_STATUS_1, &throwaway_read_result);
prv_read_register(PmicRegisters_INT_STATUS_2, &throwaway_read_result);
}
static void prv_pmic_state_change_cb(void *null) {
prv_clear_pending_interrupts();
new_timer_start(s_debounce_charger_timer, CHARGER_DEBOUNCE_MS,
prv_handle_charge_state_change, NULL, 0 /*flags*/);
}
static void prv_as3701b_interrupt_handler(bool *should_context_switch) {
system_task_add_callback_from_isr(prv_pmic_state_change_cb, NULL, should_context_switch);
}
static void prv_configure_interrupts(void) {
// Clear pending interrupts in case we were woken from standby
prv_clear_pending_interrupts();
exti_configure_pin(
BOARD_CONFIG_POWER.pmic_int, ExtiTrigger_Falling, prv_as3701b_interrupt_handler);
exti_enable(BOARD_CONFIG_POWER.pmic_int);
const uint8_t mask = (uint8_t) ~(PmicInt1_LowBat | PmicInt1_ChDet | PmicInt1_EOC);
prv_write_register(PmicRegisters_INT_MASK_1, mask);
prv_write_register(PmicRegisters_INT_MASK_2, ~0);
}
// Set up 160Hz clock which is used for VCOM.
// This setting is a divisor of 16 and a high/low duration of 195us, as
// given in the following: 1000000 / (16 * 195 * 2) = ~160Hz
static void prv_start_160hz_clock(void) {
const uint8_t pwm_high_low_time_us = (195 - 1);
prv_write_register(PmicRegisters_PWM_CNTL_H, pwm_high_low_time_us);
prv_write_register(PmicRegisters_PWM_CNTL_L, pwm_high_low_time_us);
bool success = false;
uint8_t ref_cntl;
if (prv_read_register(PmicRegisters_REFERENCE_CNTL, &ref_cntl)) {
ref_cntl |= 0x3; // Divisor of 16
prv_write_register(PmicRegisters_REFERENCE_CNTL, ref_cntl);
// Enable PWM Output on GPIO2 (Fig. 64)
// Bits 6-4: Mode, 0x1 = Output
// Bits 0-3: iosf, 0xe = PWM
uint8_t val = (1 << 4) | 0x0e;
success = prv_write_register(PmicRegisters_GPIO2_CNTL, val);
}
PBL_ASSERT(success, "Failed to start PMIC 120Hz PWM");
}
static void prv_configure_charging(void) {
// Set charge control to low current range, constant current ctl to 118mA.
bool success = false;
if (prv_set_register_bit(PmicRegisters_CHARGE_CNTL, 7, true)) {
uint8_t cntl;
if (prv_read_register(PmicRegisters_CHARGE_CURRENT_CNTL, &cntl)) {
cntl = (cntl & 0xf0) | 0x09; // 118mA when cc_range_select = 1
success = prv_write_register(PmicRegisters_CHARGE_CURRENT_CNTL, cntl);
}
}
if (!success) {
PBL_LOG(LOG_LEVEL_ERROR, "Could not set pmic charge current.");
}
// Set EOC current to 5% of ConstantCurrent
prv_set_register_bit(PmicRegisters_CHARGE_CONFIG_2, 5, false);
if (BOARD_CONFIG_POWER.charging_cutoff_voltage == 4300) {
// Set EOC to 4.30V, keep Vsup_min at 4.20V
// EOC = 3.82V + 0.02V * N
prv_write_register(PmicRegisters_CHARGE_VOLTAGE_CNTL, 0x18 | (1 << 6));
}
pmic_set_charger_state(true);
// Enable AutoResume: Resumes charging on voltage drop after EOC
prv_set_register_bit(PmicRegisters_CHARGE_CNTL, 6, true);
}
static void prv_configure_battery_measure(void) {
// Set PMIC GPIO5 (the battery measure enable pin) as an open-drain output
// with no pull and inverted output. Setting the output to 1 will drive GPIO5
// low, and setting it to 0 will cause it to float.
bool success = prv_write_register(PmicRegisters_GPIO5_CNTL, 0b10100000) &&
prv_set_pmic_gpio_outputs(0, PmicGpio5);
if (!success) {
PBL_LOG(LOG_LEVEL_ERROR, "Could not configure the battery measure control GPIO");
}
}
static bool prv_is_alive(void) {
uint8_t chip_id;
if (!prv_read_register(PmicRegisters_CHIP_ID, &chip_id)) {
return false;
}
const bool found = (chip_id == AS3701B_CHIP_ID);
if (found) {
PBL_LOG(LOG_LEVEL_DEBUG, "Found the as3701b");
} else {
PBL_LOG(LOG_LEVEL_DEBUG, "Error: read as3701b whoami byte 0x%x, expecting 0x11", chip_id);
}
return found;
}
static void prv_set_sd1_voltage(void) {
// STM32F4 running at 1.76V may trigger a Power Down Reset (PDR). The power supply has a
// tolerance of 3%. Set the voltage rail to 1.825V so our theoretical minimum should be 1.77V
uint8_t sd1_vsel;
if (prv_read_register(PmicRegisters_SD1_VOLTAGE, &sd1_vsel)) {
const uint8_t sd1_vsel_mask = 0x3f; // sd1_vsel is in first 6 bits
sd1_vsel &= ~sd1_vsel_mask;
// V_SD1 = 1.4V + (sd1_vsel - 0x40) * 25mV = 1.4V + (0x51 - 0x40) * 25mV = 1.825V
sd1_vsel |= (0x51 & sd1_vsel_mask);
prv_write_register(PmicRegisters_SD1_VOLTAGE, sd1_vsel);
}
}
static uint8_t s_last_reset_reason = 0;
static void prv_stash_last_reset_reason(void) {
uint8_t reset_cntl;
if (!prv_read_register(PmicRegisters_RESET_CNTL, &reset_cntl)) {
PBL_LOG(LOG_LEVEL_ERROR, "Failed to read the RESET_CNTL register");
return;
}
s_last_reset_reason = reset_cntl >> 4;
}
uint32_t pmic_get_last_reset_reason(void) {
return s_last_reset_reason;
}
bool pmic_init(void) {
s_debounce_charger_timer = new_timer_create();
prv_init_gpio();
if (!prv_is_alive()) {
return false;
}
prv_stash_last_reset_reason();
prv_init_pmic_gpio_outputs();
prv_set_sd1_voltage();
prv_start_160hz_clock();
prv_configure_battery_measure();
prv_configure_interrupts();
prv_configure_charging();
// Override OTP setting for 'onkey_lpress_ reset=1' so that we shutdown instead of triggering a
// reset on a long button hold
prv_set_register_bit(PmicRegisters_REFERENCE_CNTL, 5, false);
return true;
}
// On the as3701b, a power_off will cut power to all rails. We want to keep the
// RTC alive, so rather than performing a sw_power_off, enter the pmic's standby
// mode, powering down all but LDO2.
bool pmic_power_off(void) {
// Only enable interrupts that should be able to wake us out of standby
// - Wake on charger detect
const uint8_t int_mask = (uint8_t)~(PmicInt1_ChDet);
prv_write_register(PmicRegisters_INT_MASK_1, int_mask);
prv_write_register(PmicRegisters_INT_MASK_2, 0xff);
// Clear interrupt status so we're not woken immediately (read the regs)
prv_clear_pending_interrupts();
// Set Reg_Standby_mod1 to specify which rails to turn off / keep on
// - SD1, LDO1 off
// - LDO2 on
// - Disable regulator pulldowns
prv_write_register(PmicRegisters_REG_STANDBY_MOD1, 0xa);
// Set standby_mode_on (bit 4) in ReferenceControl to 1 (See Fig. 78)
if (prv_set_register_bit(PmicRegisters_REFERENCE_CNTL, 4, true)) {
while (1) {}
__builtin_unreachable();
}
return false;
}
// This is a hard power off, resulting in all rails being disabled.
// Generally, this is not desirable since we'll lose the backup domain.
// You're *probably* looking for pmic_power_off.
bool pmic_full_power_off(void) {
// ResetControl (Fig. 79)
// Bit 1: power_off - Start a reset cycle, and wait for ON or charger to complete the reset.
if (prv_set_register_bit(PmicRegisters_RESET_CNTL, 1, true)) {
while (1) {}
__builtin_unreachable();
}
return false;
}
// We have no way of directly reading Vsup with as3701b on Silk. Just assume
// that we are getting what we've configured as regulated Vsup.
uint16_t pmic_get_vsys(void) {
uint8_t cfg;
prv_read_register(PmicRegisters_CHARGE_CONFIG_1, &cfg);
const uint8_t vsup_voltage = (cfg & 0x6) >> 1;
switch (vsup_voltage) {
case 0: return 4400;
case 1: return 4500;
case 2: return 4600;
case 3: return 4700;
case 4: return 4800;
case 5: return 4900;
case 6: return 5000;
case 7: return 5500;
}
WTF;
}
bool pmic_set_charger_state(bool enable) {
// ChargerControl (Fig. 91)
// Bit 5: Enable battery charging from USB charger.
return prv_set_register_bit(PmicRegisters_CHARGE_CNTL, 5, enable);
}
bool pmic_is_charging(void) {
uint8_t status;
if (!prv_read_register(PmicRegisters_CHARGE_STATUS_1, &status)) {
#if defined (TARGET_QEMU)
// NOTE: When running on QEMU, i2c reads return false. For now, just assume a failed
// i2c read means we are charging
return true;
#else
PBL_LOG(LOG_LEVEL_DEBUG, "Failed to read charging status 1 register.");
return false;
#endif
}
// ChargerStatus1 (Fig. 97)
// Bit 0: CC
// 1: Maintain / Resume charge
// 2: Trickle charge
// 3: CV
return (status & 0x0f);
}
bool pmic_is_usb_connected(void) {
uint8_t status;
if (!prv_read_register(PmicRegisters_CHARGE_STATUS_2, &status)) {
#if TARGET_QEMU
// NOTE: When running on QEMU, i2c reads return false. For now, just assume a failed
// i2c read means we are connected to a USB cable
return true;
#endif
PBL_LOG(LOG_LEVEL_WARNING, "Failed to read charging status 2 register.");
return false;
}
// ChargerStatus2 (Fig. 98)
// Bit 2: Charger detected
return status & (1 << 2);
}
void pmic_read_chip_info(uint8_t *chip_id, uint8_t *chip_revision, uint8_t *buck1_vset) {
prv_read_register(PmicRegisters_CHIP_ID, chip_id);
prv_read_register(PmicRegisters_CHIP_REV, chip_revision);
prv_read_register(PmicRegisters_SD1_VOLTAGE, buck1_vset);
}
bool pmic_enable_battery_measure(void) {
// GPIO 5 on the pmic driven low is battery measure enable.
return prv_set_pmic_gpio_outputs(PmicGpio5, 0);
}
bool pmic_disable_battery_measure(void) {
// Set GPIO5 floating to disable battery measure.
return prv_set_pmic_gpio_outputs(0, PmicGpio5);
}
void set_ldo3_power_state(bool enabled) {
}
void set_4V5_power_state(bool enabled) {
}
void set_6V6_power_state(bool enabled) {
}
void command_pmic_read_registers(void) {
int reg;
uint8_t val;
char buffer[16];
for (uint8_t i = 0; i < ARRAY_LENGTH(s_registers); ++i) {
reg = s_registers[i];
prv_read_register(reg, &val);
prompt_send_response_fmt(buffer, sizeof(buffer), "Reg 0x%02X: 0x%02X", reg, val);
}
}
void command_pmic_status(void) {
uint8_t id, rev, buck1;
pmic_read_chip_info(&id, &rev, &buck1);
PBL_LOG(LOG_LEVEL_DEBUG, "ID: 0x%"PRIx8" REV: 0x%"PRIx8" BUCK1: 0x%"PRIx8, id, rev, buck1);
bool connected = pmic_is_usb_connected();
PBL_LOG(LOG_LEVEL_DEBUG, "USB Status: %s", (connected) ? "Connected" : "Disconnected");
bool charging = pmic_is_charging();
PBL_LOG(LOG_LEVEL_DEBUG, "Charging? %s", (charging) ? "true" : "false");
}
void command_pmic_rails(void) {
// TODO: Implement.
}

View file

@ -0,0 +1,608 @@
/*
* 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.
*/
/* This file should probably go in the stm32f4 folder */
#include "drivers/pmic.h"
#include "board/board.h"
#include "console/prompt.h"
#include "drivers/battery.h"
#include "drivers/gpio.h"
#include "drivers/i2c.h"
#include "drivers/exti.h"
#include "drivers/periph_config.h"
#include "system/logging.h"
#include "os/mutex.h"
#include "system/passert.h"
#include "kernel/util/delay.h"
#include "util/size.h"
#include "kernel/util/sleep.h"
#include "kernel/events.h"
#include "services/common/system_task.h"
#include "services/common/new_timer/new_timer.h"
#define STM32F2_COMPATIBLE
#define STM32F4_COMPATIBLE
#define STM32F7_COMPATIBLE
#include <mcu.h>
#include <stdint.h>
//! The addresses of the registers that we can read using i2c
typedef enum PmicRegisters {
PmicRegisters_CHIP_ID = 0x00,
PmicRegisters_CHIP_REV = 0x01,
PmicRegisters_STATUSA = 0x02,
PmicRegisters_STATUSB = 0x03,
PmicRegisters_INTA = 0x05,
PmicRegisters_INTB = 0x06,
PmicRegisters_INT_MASK_A = 0x07,
PmicRegisters_INT_MASK_B = 0x08,
PmicRegisters_CHG_CNTL_A = 0x0A,
PmicRegisters_CHG_CNTL_B = 0x0B,
PmicRegisters_CH_TMR = 0x0C,
PmicRegisters_BUCK1_CONFIG = 0x0D,
PmicRegisters_BUCK1_VSET = 0x0E,
PmicRegisters_BUCK2_CONFIG = 0x0F,
PmicRegisters_LDO1_CONFIG = 0x12,
PmicRegisters_LDO2_CONFIG = 0x14,
PmicRegisters_LDO3_CONFIG = 0x16,
PmicRegisters_MON_CFG = 0x19,
PmicRegisters_HAND_SHK = 0x1D,
PmicRegisters_PWR_CFG = 0x1F
} PmicRegisters;
//! The different power rails that our PMIC controls
typedef enum PmicRail {
PmicRail_BUCK1, //!< 1.2V
PmicRail_BUCK2, //!< 1.8V
PmicRail_LDO1, //!< 2.0V - Auto - RTC
PmicRail_LDO2, //!< 3.2V - Manual - FPGA
//! snowy_bb: 2.5V - Manual - MFi, Magnetometer
//! snowy_evt: 1.8V - Manual - MFi
PmicRail_LDO3
} PmicRail;
//! Gives configuration information for reading a given rail through the monitor pin.
typedef struct {
const char* name; //!< Name for the rail.
//! What ratio we need to divide by in order to bring it into the range we can sense. We can
//! only read between 0 and 1.8Vs, so we need to use the PMIC hardware to divide it down before
//! sending it to us. Valid values are 1-4.
uint8_t ratio;
//! The binary value we need to put in the register to select the rail.
uint8_t source_config;
} PmicMonConfig;
// Using the Binary constants GCC extension here, supported in GCC and Clang
// https://gcc.gnu.org/onlinedocs/gcc/Binary-constants.html
static const PmicMonConfig MON_CONFIG[] = {
{ "+VBAT", 3, 0b001 }, // 3:1
{ "+VSYS", 4, 0b010 }, // 4:1
// We only care about non-battery rails in MFG where we have the command_pmic_rails function.
#ifdef RECOVERY_FW
{ "+1V2", 1, 0b011 }, // 1:1, BUCK1
{ "+1V8", 2, 0b100 }, // 2:1, BUCK2
{ "+2V0_RTC", 2, 0b101 }, // 2:1, LDO1
{ "+3V2", 2, 0b110 }, // 2:1, LDO2
#ifdef BOARD_SNOWY_BB
{ "+2V5", 2, 0b111 }, // 2:1, LDO3
#else
{ "+1V8_MFI_MIC", 2, 0b111 }, // 2:1, LDO3
#endif // BOARD_SNOWY_BB
#endif // RECOVERY_FW
};
//! Mutex to make sure two threads aren't working with the PMIC mon value at the same time.
static PebbleMutex *s_mon_config_mutex;
static const int PMIC_MON_CONFIG_VBAT_INDEX = 0;
static const int PMIC_MON_CONFIG_VSYS_INDEX = 1;
//! Debounce timer for USB connections
static TimerID s_debounce_usb_conn_timer = TIMER_INVALID_ID;
static const int USB_CONN_DEBOUNCE_MS = 1000;
static volatile int s_interrupt_bounce_count;
/* Private Function Definitions */
static bool prv_is_alive(void);
static bool prv_set_pin_config(void);
static void prv_register_dump(int start_reg, int stop_reg);
static void prv_initialize_interrupts(void);
//! Request that the rail be used or released. Internally refcounted per rail so you don't have
//! to worry about turning this off on another client.
static bool prv_update_rail_state(PmicRail rail, bool enable);
static void prv_mon_config_lock(void) {
mutex_lock(s_mon_config_mutex);
}
static void prv_mon_config_unlock(void) {
mutex_unlock(s_mon_config_mutex);
}
static bool prv_read_register(uint8_t register_address, uint8_t *result) {
i2c_use(I2C_MAX14690);
bool rv = i2c_read_register(I2C_MAX14690, register_address, result);
i2c_release(I2C_MAX14690);
return (rv);
}
static bool prv_write_register(uint8_t register_address, uint8_t value) {
i2c_use(I2C_MAX14690);
bool rv = i2c_write_register(I2C_MAX14690, register_address, value);
i2c_release(I2C_MAX14690);
return (rv);
}
// Configure PMIC's charger settings (different from defaults -
// see https://pebbletechnology.atlassian.net/browse/PBL-15134)
static bool prv_config_charger(void) {
const uint8_t CHARGE_VOLTAGE_4300 = 0b101;
const uint8_t CHARGE_VOLTAGE_4200 = 0b011;
// [AS] HACK alert! (see PBL-19186)
// The MAX14690 state machine is stupid and kicks us into a charge complete state when the charger
// is connected and the battery voltage is within the range VBATREG < x < VBATREG - VBATRECHG
// (where VBATREG = 4.30V and VBATRECHG = 70mV (previously 170mV) for our setup). This is quite
// a likely situation because the DC internal resistance of the battery is quite high (~1Ω) and
// we reach the termination voltage at around 70% SOC. To workaround this, we set VBATREG to 4.35V
// and VBATRECHG to 70mV, turn the charger off and on again, then configure the charger to our
// desired settings. The PMIC then recovers into a charge state. This will hopefully work for
// most watches.
prv_write_register(PmicRegisters_CHG_CNTL_A, 0xCD);
pmic_set_charger_state(false);
pmic_set_charger_state(true);
const uint8_t bat_reg = (BOARD_CONFIG_POWER.charging_cutoff_voltage == 4300) ?
CHARGE_VOLTAGE_4300 : CHARGE_VOLTAGE_4200;
uint8_t chg_ctrl_a = 1 << 7 | // 1: Enable Auto-stop (default)
1 << 6 | // 1: Enable Auto-restart (default)
0 << 4 | // 0: Set battery recharge threshold to 70mV
bat_reg << 1 | // bat_Reg: Set battery charge complete voltage
1 << 0; // 1: Enable charger (default)
if (!prv_write_register(PmicRegisters_CHG_CNTL_A, chg_ctrl_a)) {
return false;
}
uint8_t chg_ctrl_b = 6 << 4 | // 6: Set precharge voltage threshold to 3.00V (default)
1 << 2 | // 1: Set precharge current to 0.1C
1 << 0; // 1: Set charge done current to 0.1C (default)
if (!prv_write_register(PmicRegisters_CHG_CNTL_B, chg_ctrl_b)) {
return false;
}
uint8_t ch_tmr = 1 << 4 | // 1: Set maintain charge timeout to 15 min
2 << 2 | // 2: Set fast charge timeout to 300 min
0 << 0; // 0: Set precharge timeout to 30 min
return prv_write_register(PmicRegisters_CH_TMR, ch_tmr);
}
/* Public Functions */
uint32_t pmic_get_last_reset_reason(void) {
// TODO: Look into if this pmic has a reset reason register which would be useful for debug
return 0;
}
bool pmic_init(void) {
s_mon_config_mutex = mutex_create();
s_debounce_usb_conn_timer = new_timer_create();
if (!prv_set_pin_config()) {
return false;
}
if (!prv_is_alive()) {
return false;
}
prv_config_charger();
prv_initialize_interrupts();
prv_update_rail_state(PmicRail_LDO2, true); // FW should bring this up
#if BOARD_ROBERT_BB2
// On Robert BB2, the BLE chip is behind LDO3, which should always be on.
prv_update_rail_state(PmicRail_LDO3, true);
#endif
if (BOARD_CONFIG.mfi_reset_pin.gpio) {
// We have access to the reset pin on the MFi. Need to hold it low before powering the 2V5
// rail in order to get the MFi into a working state.
// In the future if the MFi becomes janky again we can use this to later pull the power.
gpio_use(BOARD_CONFIG.mfi_reset_pin.gpio);
GPIO_InitTypeDef gpio_cfg;
gpio_cfg.GPIO_OType = GPIO_OType_PP;
gpio_cfg.GPIO_PuPd = GPIO_PuPd_NOPULL;
gpio_cfg.GPIO_Mode = GPIO_Mode_OUT;
gpio_cfg.GPIO_Speed = GPIO_Speed_25MHz;
gpio_cfg.GPIO_Pin = BOARD_CONFIG.mfi_reset_pin.gpio_pin;
GPIO_Init(BOARD_CONFIG.mfi_reset_pin.gpio, &gpio_cfg);
GPIO_WriteBit(BOARD_CONFIG.mfi_reset_pin.gpio, BOARD_CONFIG.mfi_reset_pin.gpio_pin, Bit_RESET);
gpio_release(BOARD_CONFIG.mfi_reset_pin.gpio);
}
return true;
}
static bool prv_update_rail_state(PmicRail rail, bool enable) {
static int8_t s_ldo2_ref_count = 0;
static int8_t s_ldo3_ref_count = 0;
int8_t *ref_count;
uint8_t rail_control_reg;
if (rail == PmicRail_LDO2) {
rail_control_reg = PmicRegisters_LDO2_CONFIG;
ref_count = &s_ldo2_ref_count;
} else if (rail == PmicRail_LDO3) {
rail_control_reg = PmicRegisters_LDO3_CONFIG;
ref_count = &s_ldo3_ref_count;
} else {
WTF;
}
uint8_t register_value;
bool success = prv_read_register(rail_control_reg, &register_value);
if (!success) {
// Failed to read the current register value
return false;
}
if (enable) {
if (*ref_count) {
(*ref_count)++;
return true;
} else {
// Set the register byte to XXXXX01X to enable the rail, mask and set
register_value = (register_value & ~0x06) | 0x02;
success = prv_write_register(rail_control_reg, register_value);
if (success) {
// We enabled the rail!
*ref_count = 1;
// We need to wait a bit for the rail to stabilize before continuing to use the device.
// It takes 2.6ms for the LDO rails to ramp.
psleep(3);
return true;
}
return false;
}
} else {
if (*ref_count <= 1) {
// Set the register byte to XXXXX00X to disable the rail, just mask
register_value = (register_value & ~0x06);
success = prv_write_register(rail_control_reg, register_value);
if (success) {
// We disabled the rail!
*ref_count = 0;
return true;
}
return false;
} else {
(*ref_count)--;
return true;
}
}
}
bool pmic_power_off(void) {
bool ret = prv_write_register(PmicRegisters_PWR_CFG, 0xB2);
if (ret) {
// Goodbye cruel world. The PMIC should be removing our power at any time now.
while(1);
__builtin_unreachable();
}
return false;
}
static bool prv_set_mon_config_register(uint8_t value) {
return prv_write_register(PmicRegisters_MON_CFG, value);
}
static bool prv_set_mon_config(const PmicMonConfig *config) {
const uint8_t ratio_config = 4 - config->ratio; // 4:1 is 0b00, 1:1 is 0b11.
const uint8_t register_value = (ratio_config << 4) | config->source_config;
bool result = prv_set_mon_config_register(register_value);
// Need to wait a short period of time for the reading to settle due to capacitance on the line.
delay_us(200);
return result;
}
bool pmic_enable_battery_measure(void) {
prv_mon_config_lock();
return prv_set_mon_config(&MON_CONFIG[PMIC_MON_CONFIG_VBAT_INDEX]);
// Don't prv_unlock, we don't want anyone else mucking with the mon config until
// pmic_disable_battery_measure is called.
}
bool pmic_disable_battery_measure(void) {
bool result = prv_set_mon_config_register(0);
// Releases the lock that was previously aquired in pmic_enable_battery_measure.
prv_mon_config_unlock();
return result;
}
uint16_t pmic_get_vsys(void) {
prv_mon_config_lock();
const PmicMonConfig *mon_config = &MON_CONFIG[PMIC_MON_CONFIG_VSYS_INDEX];
prv_set_mon_config(mon_config);
ADCVoltageMonitorReading reading = battery_read_voltage_monitor();
uint32_t millivolts = battery_convert_reading_to_millivolts(reading, mon_config->ratio, 1);
prv_set_mon_config_register(0);
prv_mon_config_unlock();
return (uint16_t)millivolts;
}
bool pmic_set_charger_state(bool enable) {
// Defaults to ON
// LSB is enable bit
uint8_t register_value;
if (!prv_read_register(PmicRegisters_CHG_CNTL_A, &register_value)) {
return false;
}
if (enable) {
register_value |= 0x01;
} else {
register_value &= ~0x01;
}
bool result = prv_write_register(PmicRegisters_CHG_CNTL_A, register_value);
return result;
}
bool pmic_is_charging(void) {
uint8_t val;
if (!prv_read_register(PmicRegisters_STATUSA, &val)) {
#if defined (TARGET_QEMU)
// NOTE: When running on QEMU, i2c reads return false. For now, just assume a failed
// i2c read means we are charging
return true;
#else
PBL_LOG(LOG_LEVEL_DEBUG, "Failed to read charging status A register");
return false;
#endif
}
uint8_t chgstat = val & 0x07; // Mask off only charging status
if (chgstat == 0x02 || // Pre-charge in progress
chgstat == 0x03 || // Fast charge, CC
chgstat == 0x04 || // Fast charge, CV
chgstat == 0x05) { // Maintain charge
return true;
} else {
return false;
}
}
bool pmic_is_usb_connected(void) {
uint8_t val;
if (!prv_read_register(PmicRegisters_STATUSB, &val)) {
#if defined (TARGET_QEMU)
// NOTE: When running on QEMU, i2c reads return false. For now, just assume a failed
// i2c read means we are connected to a USB cable
return true;
#else
PBL_LOG(LOG_LEVEL_DEBUG, "Failed to read charging status B register");
return false;
#endif
}
bool usb_connected = (val >> 3) & 1;
return usb_connected;
}
void pmic_read_chip_info(uint8_t *chip_id, uint8_t *chip_revision, uint8_t *buck1_vset) {
prv_read_register(PmicRegisters_CHIP_ID, chip_id);
prv_read_register(PmicRegisters_CHIP_REV, chip_revision);
prv_read_register(PmicRegisters_BUCK1_VSET, buck1_vset);
}
static void prv_clear_any_pending_interrupts(void) {
// Read the Int status registers to clear any pending bits.
// An interrupt wont fire if the matching bit is already set.
uint8_t throwaway_read_result;
prv_read_register(PmicRegisters_INTA, &throwaway_read_result);
prv_read_register(PmicRegisters_INTB, &throwaway_read_result);
}
static void prv_log_status_registers(const char *preamble) {
uint8_t status_a;
uint8_t status_b;
if (!prv_read_register(PmicRegisters_STATUSA, &status_a) ||
!prv_read_register(PmicRegisters_STATUSB, &status_b)) {
PBL_LOG(LOG_LEVEL_WARNING, "Failed to read status registers");
return;
}
PBL_LOG(LOG_LEVEL_INFO, "%s: StatusA = 0x%"PRIx8"; StatusB = 0x%"PRIx8, preamble, status_a,
status_b);
}
static void prv_debounce_callback(void* data) {
bool is_connected = pmic_is_usb_connected();
PBL_LOG(LOG_LEVEL_DEBUG, "Got PMIC debounced interrupt, plugged?: %s bounces: %u",
is_connected ? "YES" : "NO", s_interrupt_bounce_count);
s_interrupt_bounce_count = 0;
if (is_connected) {
// Configure our charging parameters when the charging cable is connected
prv_config_charger();
prv_log_status_registers("PMIC charger configured after charger connected");
} else {
prv_log_status_registers("PMIC charge/connection status changed");
}
PebbleEvent event = {
.type = PEBBLE_BATTERY_CONNECTION_EVENT,
.battery_connection = {
.is_connected = is_connected,
}
};
event_put(&event);
}
static void prv_handle_pmic_interrupt(void *data) {
prv_clear_any_pending_interrupts();
++s_interrupt_bounce_count;
new_timer_start(s_debounce_usb_conn_timer, USB_CONN_DEBOUNCE_MS, prv_debounce_callback,
NULL, 0 /*flags*/);
}
static void pmic_interrupt_handler(bool *should_context_switch) {
system_task_add_callback_from_isr(prv_handle_pmic_interrupt, NULL, should_context_switch);
}
/* Private Function Implementations */
static bool prv_is_alive(void) {
uint8_t val;
prv_read_register(0x00, &val);
if (val == 0x01) {
PBL_LOG(LOG_LEVEL_DEBUG, "Found the max14690");
return true;
} else {
PBL_LOG(LOG_LEVEL_DEBUG,
"Error: read max14690 whomai byte 0x%x, expecting 0x%x", val, 0x01);
return false;
}
}
static bool prv_set_pin_config(void) {
periph_config_acquire_lock();
// Initialize the GPIOs for the 4V5 & 6V6 rails
gpio_output_init(&BOARD_CONFIG_POWER.rail_4V5_ctrl, GPIO_OType_OD, GPIO_Speed_50MHz);
if (BOARD_CONFIG_POWER.rail_6V6_ctrl.gpio) {
gpio_output_init(&BOARD_CONFIG_POWER.rail_6V6_ctrl, BOARD_CONFIG_POWER.rail_6V6_ctrl_otype,
GPIO_Speed_50MHz);
}
// Interrupt config
gpio_input_init_pull_up_down(&BOARD_CONFIG_POWER.pmic_int_gpio, GPIO_PuPd_UP);
periph_config_release_lock();
return true;
}
static void prv_initialize_interrupts(void) {
exti_configure_pin(BOARD_CONFIG_POWER.pmic_int, ExtiTrigger_Falling, pmic_interrupt_handler);
exti_enable(BOARD_CONFIG_POWER.pmic_int);
// Enable the UsbOk interrupt in the IntMaskA register
prv_write_register(PmicRegisters_INT_MASK_A, 0x08);
prv_clear_any_pending_interrupts();
}
static void register_dump(int start_reg, int stop_reg) {
int reg;
uint8_t val;
char buffer[16];
for (reg = start_reg; reg <= stop_reg; reg ++) {
prv_read_register(reg, &val);
prompt_send_response_fmt(buffer, sizeof(buffer), "Reg 0x%02X: 0x%02X", reg, val);
}
}
void command_pmic_read_registers(void) {
register_dump(0x00, 0x1F);
}
#ifdef RECOVERY_FW
void command_pmic_rails(void) {
prv_mon_config_lock();
// Make sure the LDO3 rail is on before measuring it.
set_ldo3_power_state(true);
for (size_t i = 0; i < ARRAY_LENGTH(MON_CONFIG); ++i) {
prv_set_mon_config(&MON_CONFIG[i]);
ADCVoltageMonitorReading reading = battery_read_voltage_monitor();
uint32_t millivolts = battery_convert_reading_to_millivolts(reading, MON_CONFIG[i].ratio, 1);
char buffer[40];
prompt_send_response_fmt(buffer, sizeof(buffer), "%-15s: %"PRIu32" mV",
MON_CONFIG[i].name, millivolts);
}
// Turn this off again now that we're done measuring. This is refcounted so there's no concern
// that we may be turning it off if it was on before we started measuring.
set_ldo3_power_state(false);
prv_mon_config_unlock();
}
#endif // RECOVERY_FW
void set_ldo3_power_state(bool enabled) {
i2c_use(I2C_MAX14690);
prv_update_rail_state(PmicRail_LDO3, enabled);
i2c_release(I2C_MAX14690);
}
void set_4V5_power_state(bool enabled) {
gpio_output_set(&BOARD_CONFIG_POWER.rail_4V5_ctrl, enabled);
}
void set_6V6_power_state(bool enabled) {
PBL_ASSERTN(BOARD_CONFIG_POWER.rail_6V6_ctrl.gpio);
gpio_output_set(&BOARD_CONFIG_POWER.rail_6V6_ctrl, enabled);
}

29
src/fw/drivers/pwm.h Normal file
View file

@ -0,0 +1,29 @@
/*
* 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.
*/
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include "board/board.h"
void pwm_init(const PwmConfig *pwm, uint32_t resolution, uint32_t frequency);
// Note: pwm peripheral needs to be enabled before the duty cycle can be set
void pwm_set_duty_cycle(const PwmConfig *pwm, uint32_t duty_cycle);
void pwm_enable(const PwmConfig *pwm, bool enable);

Some files were not shown because too many files have changed in this diff Show more