mirror of
https://github.com/google/pebble.git
synced 2025-07-15 06:05:58 +00:00
Import of the watch repository from Pebble
This commit is contained in:
commit
3b92768480
10334 changed files with 2564465 additions and 0 deletions
394
src/fw/board/board.h
Normal file
394
src/fw/board/board.h
Normal file
|
@ -0,0 +1,394 @@
|
|||
/*
|
||||
* 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"
|
||||
|
||||
#include "drivers/button_id.h"
|
||||
#include "debug/power_tracking.h"
|
||||
|
||||
#define STM32F2_COMPATIBLE
|
||||
#define STM32F4_COMPATIBLE
|
||||
#define STM32F7_COMPATIBLE
|
||||
#include <mcu.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#define GPIO_Port_NULL ((GPIO_TypeDef *) 0)
|
||||
#define GPIO_Pin_NULL ((uint16_t)0x0000)
|
||||
//! Guaranteed invalid IRQ priority
|
||||
#define IRQ_PRIORITY_INVALID (1 << __NVIC_PRIO_BITS)
|
||||
|
||||
// This is generated in order to faciliate the check within the IRQ_MAP macro below
|
||||
enum {
|
||||
#define IRQ_DEF(num, irq) IS_VALID_IRQ__##irq,
|
||||
#include "irq_stm32.def"
|
||||
#undef IRQ_DEF
|
||||
};
|
||||
|
||||
//! Creates a trampoline to the interrupt handler defined within the driver
|
||||
#define IRQ_MAP(irq, handler, device) \
|
||||
void irq##_IRQHandler(void) { \
|
||||
handler(device); \
|
||||
} \
|
||||
_Static_assert(IS_VALID_IRQ__##irq || true, "(See comment below)")
|
||||
/*
|
||||
* The above static assert checks that the requested IRQ is valid by checking that the enum
|
||||
* value (generated above) is declared. The static assert itself will not trip, but you will get
|
||||
* a compilation error from that line if the IRQ does not exist within irq_stm32*.def.
|
||||
*/
|
||||
|
||||
// There are a lot of DMA streams and they are very straight-forward to define. Let's use some
|
||||
// macro magic to make it a bit less tedious and error-prone.
|
||||
#define CREATE_DMA_STREAM(cnum, snum) \
|
||||
static DMAStreamState s_dma##cnum##_stream##snum##_state; \
|
||||
static DMAStream DMA##cnum##_STREAM##snum##_DEVICE = { \
|
||||
.state = &s_dma##cnum##_stream##snum##_state, \
|
||||
.controller = &DMA##cnum##_DEVICE, \
|
||||
.periph = DMA##cnum##_Stream##snum, \
|
||||
.irq_channel = DMA##cnum##_Stream##snum##_IRQn, \
|
||||
}; \
|
||||
IRQ_MAP(DMA##cnum##_Stream##snum, dma_stream_irq_handler, &DMA##cnum##_STREAM##snum##_DEVICE)
|
||||
|
||||
typedef struct {
|
||||
//! One of EXTI_PortSourceGPIOX
|
||||
uint8_t exti_port_source;
|
||||
|
||||
//! Value between 0-15
|
||||
uint8_t exti_line;
|
||||
} ExtiConfig;
|
||||
|
||||
typedef enum {
|
||||
AccelThresholdLow, ///< A sensitive state used for stationary mode
|
||||
AccelThresholdHigh, ///< The accelerometer's default sensitivity
|
||||
AccelThreshold_Num,
|
||||
} AccelThreshold;
|
||||
|
||||
typedef struct {
|
||||
const char* const name; ///< Name for debugging purposes.
|
||||
GPIO_TypeDef* const gpio; ///< One of GPIOX. For example, GPIOA.
|
||||
const uint32_t gpio_pin; ///< One of GPIO_Pin_X.
|
||||
ExtiConfig exti;
|
||||
GPIOPuPd_TypeDef pull;
|
||||
} ButtonConfig;
|
||||
|
||||
typedef struct {
|
||||
GPIO_TypeDef* const gpio; ///< One of GPIOX. For example, GPIOA.
|
||||
const uint32_t gpio_pin; ///< One of GPIO_Pin_X.
|
||||
} ButtonComConfig;
|
||||
|
||||
typedef struct {
|
||||
GPIO_TypeDef* const gpio; ///< One of GPIOX. For example, GPIOA.
|
||||
const uint32_t gpio_pin; ///< One of GPIO_Pin_X.
|
||||
} InputConfig;
|
||||
|
||||
typedef struct {
|
||||
ADC_TypeDef *const adc; ///< One of ADCX. For example ADC1.
|
||||
const uint8_t adc_channel; ///< One of ADC_Channel_*
|
||||
uint32_t clock_ctrl; ///< Peripheral clock control flag
|
||||
GPIO_TypeDef* const gpio; ///< One of GPIOX. For example, GPIOA.
|
||||
const uint16_t gpio_pin; ///< One of GPIO_Pin_*
|
||||
} ADCInputConfig;
|
||||
|
||||
typedef struct {
|
||||
union {
|
||||
TIM_TypeDef* const peripheral; ///< A TIMx peripheral
|
||||
#if MICRO_FAMILY_STM32F7
|
||||
LPTIM_TypeDef* const lp_peripheral; ///< A LPTIMx peripheral
|
||||
#endif
|
||||
};
|
||||
const uint32_t config_clock; ///< One of RCC_APB1Periph_TIMx. For example, RCC_APB1Periph_TIM3.
|
||||
void (* const init)(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); ///< One of TIM_OCxInit
|
||||
void (* const preload)(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); ///< One of TIM_OCxPreloadConfig
|
||||
} TimerConfig;
|
||||
|
||||
typedef struct {
|
||||
const TimerConfig timer;
|
||||
const uint8_t irq_channel;
|
||||
} TimerIrqConfig;
|
||||
|
||||
typedef struct {
|
||||
GPIO_TypeDef* const gpio; ///< One of GPIOX. For example, GPIOA.
|
||||
const uint32_t gpio_pin; ///< One of GPIO_Pin_X.
|
||||
bool active_high; ///< Pin is active high or active low
|
||||
} OutputConfig;
|
||||
|
||||
//! Alternate function pin configuration
|
||||
//! Used to configure a pin for use by a peripheral
|
||||
typedef struct {
|
||||
GPIO_TypeDef* const gpio; ///< One of GPIOX. For example, GPIOA.
|
||||
const uint32_t gpio_pin; ///< One of GPIO_Pin_X.
|
||||
const uint16_t gpio_pin_source; ///< One of GPIO_PinSourceX.
|
||||
const uint8_t gpio_af; ///< One of GPIO_AF_X
|
||||
} AfConfig;
|
||||
|
||||
typedef struct {
|
||||
OutputConfig output;
|
||||
TimerConfig timer;
|
||||
AfConfig afcfg;
|
||||
} PwmConfig;
|
||||
|
||||
typedef struct {
|
||||
int axes_offsets[3];
|
||||
bool axes_inverts[3];
|
||||
uint32_t shake_thresholds[AccelThreshold_Num];
|
||||
uint32_t double_tap_threshold;
|
||||
} AccelConfig;
|
||||
|
||||
typedef struct {
|
||||
int axes_offsets[3];
|
||||
bool axes_inverts[3];
|
||||
} MagConfig;
|
||||
|
||||
typedef struct {
|
||||
AfConfig i2s_ck;
|
||||
AfConfig i2s_sd;
|
||||
SPI_TypeDef *spi;
|
||||
uint32_t spi_clock_ctrl;
|
||||
uint16_t gain;
|
||||
|
||||
//! Pin we use to control power to the microphone. Only used on certain boards.
|
||||
OutputConfig mic_gpio_power;
|
||||
} MicConfig;
|
||||
|
||||
typedef enum {
|
||||
OptionNotPresent = 0, // FIXME
|
||||
OptionActiveLowOpenDrain,
|
||||
OptionActiveHigh
|
||||
} PowerCtl5VOptions;
|
||||
|
||||
typedef enum {
|
||||
ActuatorOptions_Ctl = 1 << 0, ///< GPIO is used to enable / disable vibe
|
||||
ActuatorOptions_Pwm = 1 << 1, ///< PWM control
|
||||
ActuatorOptions_IssiI2C = 1 << 2, ///< I2C Device, currently used for V1_5 -> OG steel backlight
|
||||
ActuatorOptions_HBridge = 1 << 3, //< PWM actuates an H-Bridge, requires ActuatorOptions_PWM
|
||||
} ActuatorOptions;
|
||||
|
||||
typedef enum {
|
||||
CC2564A = 0,
|
||||
CC2564B,
|
||||
DA14681,
|
||||
} BluetoothController;
|
||||
|
||||
typedef struct {
|
||||
// Audio Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
const bool has_mic;
|
||||
const MicConfig mic_config;
|
||||
|
||||
// Ambient Light Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
const uint32_t ambient_light_dark_threshold;
|
||||
const uint32_t ambient_k_delta_threshold;
|
||||
const OutputConfig photo_en;
|
||||
const bool als_always_on;
|
||||
|
||||
// Debug Serial Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
const ExtiConfig dbgserial_int;
|
||||
const InputConfig dbgserial_int_gpio;
|
||||
|
||||
// MFi Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
const OutputConfig mfi_reset_pin;
|
||||
|
||||
// Display Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
const OutputConfig lcd_com; //!< This needs to be pulsed regularly to keep the sharp display fresh.
|
||||
|
||||
//! Controls power to the sharp display
|
||||
const PowerCtl5VOptions power_5v0_options;
|
||||
const OutputConfig power_ctl_5v0;
|
||||
|
||||
const uint8_t backlight_on_percent; // percent of max possible brightness
|
||||
const uint8_t backlight_max_duty_cycle_percent; // Calibrated such that the preceived brightness
|
||||
// of "backlight_on_percent = 100" (and all other values, to a reasonable
|
||||
// tolerance) is identical across all platforms. >100% isn't possible, so
|
||||
// future backlights must be at least as bright as Tintin's.
|
||||
|
||||
// FPC Pinstrap Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
const InputConfig fpc_pinstrap_1;
|
||||
const InputConfig fpc_pinstrap_2;
|
||||
|
||||
// GPIO Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
const uint16_t num_avail_gpios;
|
||||
} BoardConfig;
|
||||
|
||||
// Button Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
typedef struct {
|
||||
const ButtonConfig buttons[NUM_BUTTONS];
|
||||
const ButtonComConfig button_com;
|
||||
const bool active_high;
|
||||
} BoardConfigButton;
|
||||
|
||||
typedef struct {
|
||||
const uint32_t numerator;
|
||||
const uint32_t denominator;
|
||||
} VMonScale;
|
||||
|
||||
// Power Configuration
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
typedef struct {
|
||||
const ExtiConfig pmic_int;
|
||||
const InputConfig pmic_int_gpio;
|
||||
|
||||
//! Voltage rail control lines
|
||||
const OutputConfig rail_4V5_ctrl;
|
||||
const OutputConfig rail_6V6_ctrl;
|
||||
const GPIOOType_TypeDef rail_6V6_ctrl_otype;
|
||||
|
||||
//! Scaling factor for battery vmon
|
||||
const VMonScale battery_vmon_scale;
|
||||
//! Tells us if the USB cable plugged in.
|
||||
const InputConfig vusb_stat;
|
||||
const ExtiConfig vusb_exti;
|
||||
//! Tells us whether the charger thinks we're charging or not.
|
||||
const InputConfig chg_stat;
|
||||
//! Tell the charger to use 2x current to charge faster (MFG only).
|
||||
const OutputConfig chg_fast;
|
||||
//! Enable the charger. We may want to disable this in MFG, normally it's always on.
|
||||
const OutputConfig chg_en;
|
||||
|
||||
//! Interrupt that fires when the USB cable is plugged in
|
||||
const bool has_vusb_interrupt;
|
||||
|
||||
const bool wake_on_usb_power;
|
||||
|
||||
const int charging_cutoff_voltage;
|
||||
const int charging_status_led_voltage_compensation;
|
||||
|
||||
//! Percentage for watch only mode
|
||||
const uint8_t low_power_threshold;
|
||||
|
||||
//! Approximate hours of battery life
|
||||
const uint8_t battery_capacity_hours;
|
||||
} BoardConfigPower;
|
||||
|
||||
typedef struct {
|
||||
const AccelConfig accel_config;
|
||||
const InputConfig accel_int_gpios[2];
|
||||
const ExtiConfig accel_ints[2];
|
||||
} BoardConfigAccel;
|
||||
|
||||
typedef struct {
|
||||
const MagConfig mag_config;
|
||||
const InputConfig mag_int_gpio;
|
||||
const ExtiConfig mag_int;
|
||||
} BoardConfigMag;
|
||||
|
||||
typedef struct {
|
||||
const ActuatorOptions options;
|
||||
const OutputConfig ctl;
|
||||
const PwmConfig pwm;
|
||||
const uint16_t vsys_scale; //< Voltage to scale duty cycle to in mV. 0 if no scaling should occur.
|
||||
//< For example, Silk VBat may droop to 3.3V, so we scale down vibe
|
||||
//< duty cycle so that 100% duty cycle will always be 3.3V RMS.
|
||||
} BoardConfigActuator;
|
||||
|
||||
typedef struct {
|
||||
const OutputConfig power_en; //< Enable power supply to the accessory connector.
|
||||
const InputConfig int_gpio;
|
||||
const ExtiConfig exti;
|
||||
} BoardConfigAccessory;
|
||||
|
||||
typedef struct {
|
||||
const BluetoothController controller;
|
||||
|
||||
union {
|
||||
//! Used with CC2564x
|
||||
const OutputConfig shutdown;
|
||||
|
||||
//! Used with DA14681
|
||||
const OutputConfig reset;
|
||||
};
|
||||
|
||||
struct {
|
||||
const InputConfig int_gpio;
|
||||
const ExtiConfig int_exti;
|
||||
} wakeup;
|
||||
} BoardConfigBTCommon;
|
||||
|
||||
typedef struct {
|
||||
const bool output_enabled;
|
||||
const AfConfig af_cfg;
|
||||
const InputConfig an_cfg;
|
||||
} BoardConfigMCO1;
|
||||
|
||||
typedef struct {
|
||||
const OutputConfig cs;
|
||||
} BoardConfigBTSPI;
|
||||
|
||||
typedef struct {
|
||||
const AfConfig rx_af_cfg;
|
||||
const AfConfig tx_af_cfg;
|
||||
|
||||
USART_TypeDef* const rx_uart;
|
||||
USART_TypeDef* const tx_uart;
|
||||
|
||||
const uint32_t rx_clk_control;
|
||||
const uint32_t tx_clk_control;
|
||||
} BoardConfigBTUART;
|
||||
|
||||
// REVISIT:
|
||||
// This enum exists to allow older roll-your-own SPI
|
||||
// drivers to continue to work until they are reworked
|
||||
// to use the new SPI API. It can go away once the
|
||||
// new API is used exclusively
|
||||
|
||||
typedef enum {
|
||||
SpiPeriphClockAPB1,
|
||||
SpiPeriphClockAPB2
|
||||
} SpiPeriphClock;
|
||||
|
||||
typedef struct {
|
||||
SPI_TypeDef *spi;
|
||||
GPIO_TypeDef * const spi_gpio;
|
||||
|
||||
const uint32_t spi_clk;
|
||||
const SpiPeriphClock spi_clk_periph;
|
||||
|
||||
const AfConfig mosi;
|
||||
const AfConfig clk;
|
||||
const OutputConfig cs;
|
||||
|
||||
const OutputConfig on_ctrl;
|
||||
const GPIOOType_TypeDef on_ctrl_otype;
|
||||
} BoardConfigSharpDisplay;
|
||||
|
||||
typedef const struct DMARequest DMARequest;
|
||||
typedef const struct UARTDevice UARTDevice;
|
||||
typedef const struct SPIBus SPIBus;
|
||||
typedef const struct SPISlavePort SPISlavePort;
|
||||
typedef const struct I2CBus I2CBus;
|
||||
typedef const struct I2CSlavePort I2CSlavePort;
|
||||
typedef const struct HRMDevice HRMDevice;
|
||||
typedef const struct VoltageMonitorDevice VoltageMonitorDevice;
|
||||
typedef const struct TemperatureSensor TemperatureSensor;
|
||||
typedef const struct MicDevice MicDevice;
|
||||
typedef const struct QSPIPort QSPIPort;
|
||||
typedef const struct QSPIFlash QSPIFlash;
|
||||
typedef const struct ICE40LPDevice ICE40LPDevice;
|
||||
typedef const struct TouchSensor TouchSensor;
|
||||
|
||||
void board_early_init(void);
|
||||
void board_init(void);
|
||||
|
||||
#include "board_definitions.h"
|
64
src/fw/board/board_definitions.h
Normal file
64
src/fw/board/board_definitions.h
Normal 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
|
||||
|
||||
// FIXME: PBL-21049 Fix platform abstraction and board definition scheme
|
||||
#if BOARD_EV2_4
|
||||
#include "boards/board_ev2_4.h" // shipped as Pebble 1.0
|
||||
#elif BOARD_BB2
|
||||
#include "boards/board_bb2.h"
|
||||
#elif BOARD_V1_5
|
||||
#include "boards/board_v1_5.h" // prototypes for Pebble 1.3/Pebble 1.5
|
||||
#elif BOARD_V2_0
|
||||
#include "boards/board_v2_0.h" // prototypes for Pebble 2.0
|
||||
#elif BOARD_SNOWY_BB
|
||||
#include "boards/board_snowy_bb.h" // prototypes for Snowy bigboard
|
||||
#elif BOARD_SNOWY_EVT
|
||||
#include "boards/board_snowy_evt.h" // prototypes for Snowy EVT
|
||||
#elif BOARD_SNOWY_EVT2
|
||||
#include "boards/board_snowy.h" // prototypes for Snowy EVT2
|
||||
#elif BOARD_SNOWY_BB2
|
||||
#include "boards/board_snowy.h" // prototypes for Snowy BB2 are identical to EVT2
|
||||
#elif BOARD_SNOWY_DVT
|
||||
#include "boards/board_snowy.h" // prototypes for DVT, electrically identical to EVT2
|
||||
#elif BOARD_SPALDING_BB2
|
||||
#include "boards/board_snowy.h" // prototypes for Spalding BB2, Snowy BB2s with a Spalding display
|
||||
#elif BOARD_SPALDING_EVT
|
||||
#include "boards/board_spalding_evt.h" // prototypes for Spalding EVT
|
||||
#elif BOARD_SPALDING
|
||||
#include "boards/board_spalding_evt.h" // prototypes for Spalding MP
|
||||
#elif BOARD_SNOWY_S3
|
||||
#include "boards/board_snowy.h" // prototypes for Spalding EVT, electrically identical to Snowy
|
||||
#elif BOARD_SILK_EVT
|
||||
#include "boards/board_silk.h"
|
||||
#elif BOARD_SILK_BB
|
||||
#include "boards/board_silk.h"
|
||||
#elif BOARD_SILK_BB2
|
||||
#include "boards/board_silk.h"
|
||||
#elif BOARD_SILK
|
||||
#include "boards/board_silk.h"
|
||||
#elif BOARD_CUTTS_BB
|
||||
#include "boards/board_robert.h" // prototypes for Cutts
|
||||
#elif BOARD_ROBERT_BB
|
||||
#include "boards/board_robert.h" // prototypes for Robert BB
|
||||
#elif BOARD_ROBERT_BB2
|
||||
#include "boards/board_robert.h" // prototypes for Robert BB2
|
||||
#elif BOARD_ROBERT_EVT
|
||||
#include "boards/board_robert.h" // prototypes for Robert EVT
|
||||
#else
|
||||
#error "Unknown board definition"
|
||||
#endif
|
247
src/fw/board/boards/board_bb2.c
Normal file
247
src/fw/board/boards/board_bb2.c
Normal file
|
@ -0,0 +1,247 @@
|
|||
/*
|
||||
* 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/i2c_definitions.h"
|
||||
#include "drivers/stm32f2/dma_definitions.h"
|
||||
#include "drivers/stm32f2/i2c_hal_definitions.h"
|
||||
#include "drivers/stm32f2/uart_definitions.h"
|
||||
#include "drivers/voltage_monitor.h"
|
||||
|
||||
// DMA Controllers
|
||||
|
||||
static DMAControllerState s_dma1_state;
|
||||
static DMAController DMA1_DEVICE = {
|
||||
.state = &s_dma1_state,
|
||||
.periph = DMA1,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA1,
|
||||
};
|
||||
|
||||
static DMAControllerState s_dma2_state;
|
||||
static DMAController DMA2_DEVICE = {
|
||||
.state = &s_dma2_state,
|
||||
.periph = DMA2,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA2,
|
||||
};
|
||||
|
||||
// DMA Streams
|
||||
|
||||
CREATE_DMA_STREAM(1, 1); // DMA1_STREAM1_DEVICE - Debug UART RX
|
||||
CREATE_DMA_STREAM(1, 4); // DMA1_STREAM4_DEVICE - Sharp SPI TX
|
||||
|
||||
// DMA Requests
|
||||
|
||||
static DMARequestState s_dbg_uart_dma_request_state;
|
||||
static DMARequest DBG_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_dbg_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM1_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = 0, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_sharp_spi_tx_dma_request_state;
|
||||
static DMARequest SHARP_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_sharp_spi_tx_dma_request_state,
|
||||
.stream = &DMA1_STREAM4_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
DMARequest * const SHARP_SPI_TX_DMA = &SHARP_SPI_TX_DMA_REQUEST;
|
||||
|
||||
|
||||
// UART DEVICES
|
||||
|
||||
#if TARGET_QEMU
|
||||
static UARTDeviceState s_qemu_uart_state;
|
||||
static UARTDevice QEMU_UART_DEVICE = {
|
||||
.state = &s_qemu_uart_state,
|
||||
// GPIO? Where we're going, we don't need GPIO. (connected to QEMU)
|
||||
.periph = USART2,
|
||||
.irq_channel = USART2_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2
|
||||
};
|
||||
UARTDevice * const QEMU_UART = &QEMU_UART_DEVICE;
|
||||
IRQ_MAP(USART2, uart_irq_handler, QEMU_UART);
|
||||
#endif
|
||||
|
||||
static UARTDeviceState s_dbg_uart_state;
|
||||
static UARTDevice DBG_UART_DEVICE = {
|
||||
.state = &s_dbg_uart_state,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.rx_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.periph = USART3,
|
||||
.irq_channel = USART3_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART3,
|
||||
.rx_dma = &DBG_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const DBG_UART = &DBG_UART_DEVICE;
|
||||
IRQ_MAP(USART3, uart_irq_handler, DBG_UART);
|
||||
|
||||
|
||||
// I2C DEVICES
|
||||
|
||||
static I2CBusState I2C_MAIN_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_MAIN_BUS_HAL = {
|
||||
.i2c = I2C1,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C1,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_16_9,
|
||||
.ev_irq_channel = I2C1_EV_IRQn,
|
||||
.er_irq_channel = I2C1_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_MAIN_BUS = {
|
||||
.state = &I2C_MAIN_BUS_STATE,
|
||||
.hal = &I2C_MAIN_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C1,
|
||||
.name = "I2C_MAIN"
|
||||
};
|
||||
|
||||
extern void i2c_rail_ctl_pin(I2CBus *device, bool enable);
|
||||
|
||||
static I2CBusState I2C_2V5_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_2V5_BUS_HAL = {
|
||||
.i2c = I2C2,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C2,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_2,
|
||||
.ev_irq_channel = I2C2_EV_IRQn,
|
||||
.er_irq_channel = I2C2_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_2V5_BUS = {
|
||||
.state = &I2C_2V5_BUS_STATE,
|
||||
.hal = &I2C_2V5_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C2,
|
||||
.rail_gpio = {
|
||||
.gpio = GPIOH,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
.active_high = true
|
||||
},
|
||||
.rail_ctl_fn = i2c_rail_ctl_pin,
|
||||
.name = "I2C_2V5"
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_LIS3DH = {
|
||||
.bus = &I2C_MAIN_BUS,
|
||||
.address = 0x32
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MFI = {
|
||||
.bus = &I2C_2V5_BUS,
|
||||
.address = 0x20
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAG3110 = {
|
||||
.bus = &I2C_2V5_BUS,
|
||||
.address = 0x1C
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_LED = {
|
||||
.bus = &I2C_MAIN_BUS,
|
||||
.address = 0xC8
|
||||
};
|
||||
|
||||
I2CSlavePort * const I2C_LIS3DH = &I2C_SLAVE_LIS3DH;
|
||||
I2CSlavePort * const I2C_MFI = &I2C_SLAVE_MFI;
|
||||
I2CSlavePort * const I2C_MAG3110 = &I2C_SLAVE_MAG3110;
|
||||
I2CSlavePort * const I2C_LED = &I2C_SLAVE_LED;
|
||||
|
||||
IRQ_MAP(I2C1_EV, i2c_hal_event_irq_handler, &I2C_MAIN_BUS);
|
||||
IRQ_MAP(I2C1_ER, i2c_hal_error_irq_handler, &I2C_MAIN_BUS);
|
||||
IRQ_MAP(I2C2_EV, i2c_hal_event_irq_handler, &I2C_2V5_BUS);
|
||||
IRQ_MAP(I2C2_ER, i2c_hal_error_irq_handler, &I2C_2V5_BUS);
|
||||
|
||||
|
||||
// VOLTAGE MONITOR DEVICES
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_ALS_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_12,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_BATTERY_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_10,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
},
|
||||
};
|
||||
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS = &VOLTAGE_MONITOR_ALS_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY = &VOLTAGE_MONITOR_BATTERY_DEVICE;
|
||||
|
||||
void board_early_init(void) {
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
i2c_init(&I2C_MAIN_BUS);
|
||||
i2c_init(&I2C_2V5_BUS);
|
||||
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_ALS);
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_BATTERY);
|
||||
}
|
175
src/fw/board/boards/board_bb2.h
Normal file
175
src/fw/board/boards/board_bb2.h
Normal file
|
@ -0,0 +1,175 @@
|
|||
/*
|
||||
* 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/button.h"
|
||||
#include "services/imu/units.h"
|
||||
#include "util/size.h"
|
||||
|
||||
#define BOARD_LSE_MODE RCC_LSE_ON
|
||||
|
||||
static const BoardConfig BOARD_CONFIG = {
|
||||
.ambient_light_dark_threshold = 3000,
|
||||
.ambient_k_delta_threshold = 96,
|
||||
.photo_en = { GPIOD, GPIO_Pin_2, true },
|
||||
|
||||
.dbgserial_int = { EXTI_PortSourceGPIOC, 11 },
|
||||
|
||||
.lcd_com = { GPIOB, GPIO_Pin_1, true },
|
||||
|
||||
.power_ctl_5v0 = { GPIOC, GPIO_Pin_5, false },
|
||||
|
||||
.backlight_on_percent = 25,
|
||||
.backlight_max_duty_cycle_percent = 100,
|
||||
|
||||
.power_5v0_options = OptionActiveLowOpenDrain,
|
||||
|
||||
.has_mic = false,
|
||||
};
|
||||
|
||||
static const BoardConfigButton BOARD_CONFIG_BUTTON = {
|
||||
.buttons = {
|
||||
[BUTTON_ID_BACK] = { "Back", GPIOC, GPIO_Pin_3, { EXTI_PortSourceGPIOC, 3 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_UP] = { "Up", GPIOA, GPIO_Pin_2, { EXTI_PortSourceGPIOA, 2 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_SELECT] = { "Select", GPIOC, GPIO_Pin_6, { EXTI_PortSourceGPIOC, 6 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_DOWN] = { "Down", GPIOA, GPIO_Pin_1, { EXTI_PortSourceGPIOA, 1 }, GPIO_PuPd_NOPULL },
|
||||
},
|
||||
|
||||
.button_com = { GPIOA, GPIO_Pin_0 },
|
||||
.active_high = false,
|
||||
};
|
||||
|
||||
static const BoardConfigPower BOARD_CONFIG_POWER = {
|
||||
.vusb_stat = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_13,
|
||||
},
|
||||
.vusb_exti = { EXTI_PortSourceGPIOC, 13 },
|
||||
|
||||
.chg_stat = { GPIOH, GPIO_Pin_1 },
|
||||
.chg_fast = { GPIOB, GPIO_Pin_6 },
|
||||
.chg_en = { GPIOB, GPIO_Pin_9 },
|
||||
|
||||
.has_vusb_interrupt = true,
|
||||
|
||||
.wake_on_usb_power = true,
|
||||
|
||||
.charging_status_led_voltage_compensation = 0,
|
||||
|
||||
.low_power_threshold = 5,
|
||||
.battery_capacity_hours = 144,
|
||||
};
|
||||
|
||||
static const BoardConfigAccel BOARD_CONFIG_ACCEL = {
|
||||
.accel_config = {
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = true,
|
||||
.axes_inverts[AXIS_Y] = false,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
.shake_thresholds[AccelThresholdHigh] = 0x7f,
|
||||
.shake_thresholds[AccelThresholdLow] = 0xa,
|
||||
},
|
||||
.accel_ints = {
|
||||
[0] = { EXTI_PortSourceGPIOC, 8 },
|
||||
[1] = { EXTI_PortSourceGPIOC, 9 }
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMag BOARD_CONFIG_MAG = {
|
||||
.mag_config = { // align raw mag data with accel coords (ENU)
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
},
|
||||
.mag_int = { EXTI_PortSourceGPIOC, 4 },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_VIBE = {
|
||||
.options = ActuatorOptions_Ctl,
|
||||
.ctl = { GPIOB, GPIO_Pin_13, true },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_BACKLIGHT = {
|
||||
.options = ActuatorOptions_Pwm,
|
||||
.ctl = {0},
|
||||
.pwm = {
|
||||
.output = { GPIOB, GPIO_Pin_5, true },
|
||||
.timer = {
|
||||
.peripheral = TIM3,
|
||||
.config_clock = RCC_APB1Periph_TIM3,
|
||||
.init = TIM_OC2Init,
|
||||
.preload = TIM_OC2PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOB, GPIO_Pin_5, GPIO_PinSource5, GPIO_AF_TIM3 },
|
||||
},
|
||||
};
|
||||
|
||||
#define BOARD_BT_USART_IRQ_HANDLER USART1_IRQHandler
|
||||
static const BoardConfigBTCommon BOARD_CONFIG_BT_COMMON = {
|
||||
.controller = CC2564A,
|
||||
.shutdown = { GPIOA, GPIO_Pin_3, false},
|
||||
.wakeup = {
|
||||
.int_gpio = { GPIOC, GPIO_Pin_12 },
|
||||
.int_exti = { EXTI_PortSourceGPIOC, 12 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMCO1 BOARD_CONFIG_MCO1 = {
|
||||
.output_enabled = true,
|
||||
.af_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_MCO,
|
||||
},
|
||||
.an_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigSharpDisplay BOARD_CONFIG_DISPLAY = {
|
||||
.spi = SPI2,
|
||||
.spi_gpio = GPIOB,
|
||||
.spi_clk = RCC_APB1Periph_SPI2,
|
||||
.spi_clk_periph = SpiPeriphClockAPB1,
|
||||
|
||||
.clk = { GPIOB, GPIO_Pin_13, GPIO_PinSource13, GPIO_AF_SPI2 },
|
||||
.mosi = { GPIOB, GPIO_Pin_15, GPIO_PinSource15, GPIO_AF_SPI2 },
|
||||
.cs = { GPIOB, GPIO_Pin_12, true },
|
||||
|
||||
.on_ctrl = { GPIOB, GPIO_Pin_14, true },
|
||||
.on_ctrl_otype = GPIO_OType_OD,
|
||||
};
|
||||
|
||||
extern DMARequest * const SHARP_SPI_TX_DMA;
|
||||
|
||||
extern UARTDevice * const QEMU_UART;
|
||||
extern UARTDevice * const DBG_UART;
|
||||
|
||||
extern I2CSlavePort * const I2C_LIS3DH;
|
||||
extern I2CSlavePort * const I2C_MFI;
|
||||
extern I2CSlavePort * const I2C_MAG3110;
|
||||
extern I2CSlavePort * const I2C_LED;
|
||||
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS;
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY;
|
241
src/fw/board/boards/board_ev2_4.c
Normal file
241
src/fw/board/boards/board_ev2_4.c
Normal 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 "board/board.h"
|
||||
|
||||
#include "drivers/i2c_definitions.h"
|
||||
#include "drivers/stm32f2/dma_definitions.h"
|
||||
#include "drivers/stm32f2/i2c_hal_definitions.h"
|
||||
#include "drivers/stm32f2/uart_definitions.h"
|
||||
#include "drivers/voltage_monitor.h"
|
||||
|
||||
// DMA Controllers
|
||||
|
||||
static DMAControllerState s_dma1_state;
|
||||
static DMAController DMA1_DEVICE = {
|
||||
.state = &s_dma1_state,
|
||||
.periph = DMA1,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA1,
|
||||
};
|
||||
|
||||
static DMAControllerState s_dma2_state;
|
||||
static DMAController DMA2_DEVICE = {
|
||||
.state = &s_dma2_state,
|
||||
.periph = DMA2,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA2,
|
||||
};
|
||||
|
||||
// DMA Streams
|
||||
|
||||
CREATE_DMA_STREAM(1, 1); // DMA1_STREAM1_DEVICE - Debug UART RX
|
||||
CREATE_DMA_STREAM(1, 4); // DMA1_STREAM4_DEVICE - Sharp SPI TX
|
||||
|
||||
// DMA Requests
|
||||
|
||||
static DMARequestState s_dbg_uart_dma_request_state;
|
||||
static DMARequest DBG_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_dbg_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM1_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_sharp_spi_tx_dma_request_state;
|
||||
static DMARequest SHARP_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_sharp_spi_tx_dma_request_state,
|
||||
.stream = &DMA1_STREAM4_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
DMARequest * const SHARP_SPI_TX_DMA = &SHARP_SPI_TX_DMA_REQUEST;
|
||||
|
||||
|
||||
// UART DEVICES
|
||||
|
||||
#if TARGET_QEMU
|
||||
static UARTDeviceState s_qemu_uart_state;
|
||||
static UARTDevice QEMU_UART_DEVICE = {
|
||||
.state = &s_qemu_uart_state,
|
||||
// GPIO? Where we're going, we don't need GPIO. (connected to QEMU)
|
||||
.periph = USART2,
|
||||
.irq_channel = USART2_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2
|
||||
};
|
||||
UARTDevice * const QEMU_UART = &QEMU_UART_DEVICE;
|
||||
IRQ_MAP(USART2, uart_irq_handler, QEMU_UART);
|
||||
#endif
|
||||
|
||||
static UARTDeviceState s_dbg_uart_state;
|
||||
static UARTDevice DBG_UART_DEVICE = {
|
||||
.state = &s_dbg_uart_state,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.rx_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.periph = USART3,
|
||||
.irq_channel = USART3_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART3,
|
||||
.rx_dma = &DBG_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const DBG_UART = &DBG_UART_DEVICE;
|
||||
IRQ_MAP(USART3, uart_irq_handler, DBG_UART);
|
||||
|
||||
|
||||
// I2C DEVICES
|
||||
|
||||
static I2CBusState I2C_MAIN_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_MAIN_BUS_HAL = {
|
||||
.i2c = I2C1,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C1,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_16_9,
|
||||
.ev_irq_channel = I2C1_EV_IRQn,
|
||||
.er_irq_channel = I2C1_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_MAIN_BUS = {
|
||||
.state = &I2C_MAIN_BUS_STATE,
|
||||
.hal = &I2C_MAIN_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C1,
|
||||
.name = "I2C_MAIN"
|
||||
};
|
||||
|
||||
extern void i2c_rail_ctl_pin(I2CBus *device, bool enable);
|
||||
|
||||
static I2CBusState I2C_2V5_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_2V5_BUS_HAL = {
|
||||
.i2c = I2C2,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C2,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_2,
|
||||
.ev_irq_channel = I2C2_EV_IRQn,
|
||||
.er_irq_channel = I2C2_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_2V5_BUS = {
|
||||
.state = &I2C_2V5_BUS_STATE,
|
||||
.hal = &I2C_2V5_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C2,
|
||||
.rail_gpio = {
|
||||
.gpio = GPIOH,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
.active_high = true
|
||||
},
|
||||
.rail_ctl_fn = i2c_rail_ctl_pin,
|
||||
.name = "I2C_2V5"
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_LIS3DH = {
|
||||
.bus = &I2C_MAIN_BUS,
|
||||
.address = 0x32
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MFI = {
|
||||
.bus = &I2C_2V5_BUS,
|
||||
.address = 0x20
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAG3110 = {
|
||||
.bus = &I2C_2V5_BUS,
|
||||
.address = 0x1C
|
||||
};
|
||||
|
||||
I2CSlavePort * const I2C_LIS3DH = &I2C_SLAVE_LIS3DH;
|
||||
I2CSlavePort * const I2C_MFI = &I2C_SLAVE_MFI;
|
||||
I2CSlavePort * const I2C_MAG3110 = &I2C_SLAVE_MAG3110;
|
||||
|
||||
IRQ_MAP(I2C1_EV, i2c_hal_event_irq_handler, &I2C_MAIN_BUS);
|
||||
IRQ_MAP(I2C1_ER, i2c_hal_error_irq_handler, &I2C_MAIN_BUS);
|
||||
IRQ_MAP(I2C2_EV, i2c_hal_event_irq_handler, &I2C_2V5_BUS);
|
||||
IRQ_MAP(I2C2_ER, i2c_hal_error_irq_handler, &I2C_2V5_BUS);
|
||||
|
||||
|
||||
// VOLTAGE MONITOR DEVICES
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_ALS_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_12,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_BATTERY_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_10,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
},
|
||||
};
|
||||
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS = &VOLTAGE_MONITOR_ALS_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY = &VOLTAGE_MONITOR_BATTERY_DEVICE;
|
||||
|
||||
void board_early_init(void) {
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
i2c_init(&I2C_MAIN_BUS);
|
||||
i2c_init(&I2C_2V5_BUS);
|
||||
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_ALS);
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_BATTERY);
|
||||
}
|
172
src/fw/board/boards/board_ev2_4.h
Normal file
172
src/fw/board/boards/board_ev2_4.h
Normal file
|
@ -0,0 +1,172 @@
|
|||
/*
|
||||
* 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/battery.h"
|
||||
#include "drivers/button.h"
|
||||
#include "drivers/imu/lis3dh/lis3dh.h"
|
||||
#include "drivers/imu/mag3110/mag3110.h"
|
||||
#include "services/imu/units.h"
|
||||
#include "util/size.h"
|
||||
|
||||
#define BOARD_LSE_MODE RCC_LSE_ON
|
||||
|
||||
static const BoardConfig BOARD_CONFIG = {
|
||||
.photo_en = { GPIOD, GPIO_Pin_2, true },
|
||||
.ambient_light_dark_threshold = 3180,
|
||||
.ambient_k_delta_threshold = 96,
|
||||
|
||||
.lcd_com = { GPIOB, GPIO_Pin_1, true },
|
||||
|
||||
.dbgserial_int = { EXTI_PortSourceGPIOC, 11 },
|
||||
|
||||
.power_5v0_options = OptionActiveLowOpenDrain,
|
||||
.power_ctl_5v0 = { GPIOC, GPIO_Pin_5, false },
|
||||
|
||||
.backlight_on_percent = 25,
|
||||
.backlight_max_duty_cycle_percent = 100,
|
||||
|
||||
.has_mic = false,
|
||||
};
|
||||
|
||||
static const BoardConfigButton BOARD_CONFIG_BUTTON = {
|
||||
.buttons = {
|
||||
[BUTTON_ID_BACK] = { "Back", GPIOC, GPIO_Pin_3, { EXTI_PortSourceGPIOC, 3 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_UP] = { "Up", GPIOA, GPIO_Pin_2, { EXTI_PortSourceGPIOA, 2 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_SELECT] = { "Select", GPIOC, GPIO_Pin_6, { EXTI_PortSourceGPIOC, 6 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_DOWN] = { "Down", GPIOA, GPIO_Pin_1, { EXTI_PortSourceGPIOA, 1 }, GPIO_PuPd_NOPULL },
|
||||
},
|
||||
|
||||
.button_com = { GPIOA, GPIO_Pin_0 },
|
||||
.active_high = false,
|
||||
};
|
||||
|
||||
static const BoardConfigPower BOARD_CONFIG_POWER = {
|
||||
.vusb_stat = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_12,
|
||||
},
|
||||
.vusb_exti = { EXTI_PortSourceGPIOC, 12 },
|
||||
.chg_stat = { GPIOH, GPIO_Pin_1 },
|
||||
|
||||
.has_vusb_interrupt = true,
|
||||
.charging_status_led_voltage_compensation = 0,
|
||||
|
||||
.wake_on_usb_power = false,
|
||||
|
||||
.low_power_threshold = 3,
|
||||
.battery_capacity_hours = 144,
|
||||
};
|
||||
|
||||
static const BoardConfigAccel BOARD_CONFIG_ACCEL = {
|
||||
.accel_config = {
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = true,
|
||||
.axes_inverts[AXIS_Y] = false,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
.shake_thresholds[AccelThresholdHigh] = 0x7f,
|
||||
.shake_thresholds[AccelThresholdLow] = 0xa,
|
||||
},
|
||||
.accel_ints = {
|
||||
[0] = { EXTI_PortSourceGPIOC, 8 },
|
||||
[1] = { EXTI_PortSourceGPIOC, 9 }
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMag BOARD_CONFIG_MAG = {
|
||||
.mag_config = { // align raw mag data with accel coords (ENU)
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
},
|
||||
.mag_int = { EXTI_PortSourceGPIOC, 4 },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_VIBE = {
|
||||
.options = ActuatorOptions_Ctl,
|
||||
.ctl = { GPIOB, GPIO_Pin_0, true },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_BACKLIGHT = {
|
||||
.options = ActuatorOptions_Pwm,
|
||||
.ctl = {0},
|
||||
.pwm = {
|
||||
.output = { GPIOB, GPIO_Pin_5, true },
|
||||
.timer = {
|
||||
.peripheral = TIM3,
|
||||
.config_clock = RCC_APB1Periph_TIM3,
|
||||
.init = TIM_OC2Init,
|
||||
.preload = TIM_OC2PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOB, GPIO_Pin_5, GPIO_PinSource5, GPIO_AF_TIM3 },
|
||||
},
|
||||
};
|
||||
|
||||
#define BOARD_BT_USART_IRQ_HANDLER USART1_IRQHandler
|
||||
static const BoardConfigBTCommon BOARD_CONFIG_BT_COMMON = {
|
||||
.controller = CC2564A,
|
||||
.shutdown = { GPIOA, GPIO_Pin_3, false},
|
||||
.wakeup = {
|
||||
.int_gpio = { GPIOC, GPIO_Pin_13 },
|
||||
.int_exti = { EXTI_PortSourceGPIOC, 13 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMCO1 BOARD_CONFIG_MCO1 = {
|
||||
.output_enabled = true,
|
||||
.af_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_MCO,
|
||||
},
|
||||
.an_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigSharpDisplay BOARD_CONFIG_DISPLAY = {
|
||||
.spi = SPI2,
|
||||
.spi_gpio = GPIOB,
|
||||
.spi_clk = RCC_APB1Periph_SPI2,
|
||||
.spi_clk_periph = SpiPeriphClockAPB1,
|
||||
|
||||
.clk = { GPIOB, GPIO_Pin_13, GPIO_PinSource13, GPIO_AF_SPI2 },
|
||||
.mosi = { GPIOB, GPIO_Pin_15, GPIO_PinSource15, GPIO_AF_SPI2 },
|
||||
.cs = { GPIOB, GPIO_Pin_12, true },
|
||||
|
||||
.on_ctrl = { GPIOB, GPIO_Pin_14, true },
|
||||
.on_ctrl_otype = GPIO_OType_OD,
|
||||
};
|
||||
|
||||
extern DMARequest * const SHARP_SPI_TX_DMA;
|
||||
|
||||
extern UARTDevice * const QEMU_UART;
|
||||
extern UARTDevice * const DBG_UART;
|
||||
|
||||
extern I2CSlavePort * const I2C_LIS3DH;
|
||||
extern I2CSlavePort * const I2C_MFI;
|
||||
extern I2CSlavePort * const I2C_MAG3110;
|
||||
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS;
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY;
|
726
src/fw/board/boards/board_robert.c
Normal file
726
src/fw/board/boards/board_robert.c
Normal file
|
@ -0,0 +1,726 @@
|
|||
/*
|
||||
* 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/display/ice40lp/ice40lp_definitions.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/flash/qspi_flash_definitions.h"
|
||||
#include "drivers/i2c_definitions.h"
|
||||
#include "drivers/pmic.h"
|
||||
#include "drivers/qspi_definitions.h"
|
||||
#include "drivers/stm32f2/dma_definitions.h"
|
||||
#include "drivers/stm32f2/spi_definitions.h"
|
||||
#include "drivers/stm32f7/i2c_hal_definitions.h"
|
||||
#include "drivers/stm32f7/uart_definitions.h"
|
||||
#include "drivers/temperature.h"
|
||||
#include "drivers/touch/ewd1000/touch_sensor_definitions.h"
|
||||
#include "drivers/voltage_monitor.h"
|
||||
#include "flash_region/flash_region.h"
|
||||
#include "util/units.h"
|
||||
|
||||
#define DIALOG_SPI_DMA_PRIORITY (0x0b)
|
||||
// Make sure that the DMA IRQ is handled before EXTI:
|
||||
// See comments in host/host_transport.c prv_int_exti_cb()
|
||||
_Static_assert(DIALOG_SPI_DMA_PRIORITY < EXTI_PRIORITY, "Dialog SPI DMA priority too low!");
|
||||
|
||||
// DMA Controllers
|
||||
|
||||
static DMAControllerState s_dma1_state;
|
||||
static DMAController DMA1_DEVICE = {
|
||||
.state = &s_dma1_state,
|
||||
.periph = DMA1,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA1,
|
||||
};
|
||||
|
||||
static DMAControllerState s_dma2_state;
|
||||
static DMAController DMA2_DEVICE = {
|
||||
.state = &s_dma2_state,
|
||||
.periph = DMA2,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA2,
|
||||
};
|
||||
|
||||
// DMA Streams
|
||||
|
||||
CREATE_DMA_STREAM(1, 1); // DMA1_STREAM1_DEVICE - Debug UART RX
|
||||
CREATE_DMA_STREAM(1, 2); // DMA1_STREAM2_DEVICE - Accessory UART RX
|
||||
CREATE_DMA_STREAM(2, 0); // DMA2_STREAM0_DEVICE - Dialog SPI RX
|
||||
CREATE_DMA_STREAM(2, 1); // DMA2_STREAM1_DEVICE - Dialog SPI TX
|
||||
CREATE_DMA_STREAM(2, 2); // DMA2_STREAM2_DEVICE - Compositor DMA
|
||||
CREATE_DMA_STREAM(2, 4); // DMA2_STREAM4_DEVICE - DFSDM
|
||||
CREATE_DMA_STREAM(2, 5); // DMA2_STREAM5_DEVICE - ICE40LP TX
|
||||
CREATE_DMA_STREAM(2, 7); // DMA2_STREAM7_DEVICE - QSPI
|
||||
|
||||
// DMA Requests
|
||||
// - On DMA1 we have "Debug UART RX" and "Accessory UART RX". The former is never used in a sealed
|
||||
// watch, and the latter is only sometimes used in a sealed watch. So, we don't really care about
|
||||
// their priorities and set them both to "High".
|
||||
// - On DMA2 we have "Dialog SPI RX", "Dialog SPI TX", "Compositor DMA", "DFSDM", "ICE40LP TX", and
|
||||
// "QSPI". We want "DFSDM" and "Dialog SPI RX" to have a very high priority because their
|
||||
// peripheral buffers may overflow if the DMA stream doesn't read from them in a while. After
|
||||
// that, we want communication with the BLE chip and QSPI reads to be low-latency so give them a
|
||||
// high priority. Lastly, writing to the display prevents us from rendering the next frame, so
|
||||
// give the "ICE40LP TX" and "Compositor" DMAs a medium priority.
|
||||
|
||||
static DMARequestState s_dbg_uart_dma_request_state;
|
||||
static DMARequest DBG_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_dbg_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM1_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_accessory_uart_dma_request_state;
|
||||
static DMARequest ACCESSORY_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_accessory_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM2_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_dialog_spi_rx_dma_request_state;
|
||||
static DMARequest DIALOG_SPI_RX_DMA_REQUEST = {
|
||||
.state = &s_dialog_spi_rx_dma_request_state,
|
||||
.stream = &DMA2_STREAM0_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = DIALOG_SPI_DMA_PRIORITY,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_dialog_spi_tx_dma_request_state;
|
||||
static DMARequest DIALOG_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_dialog_spi_tx_dma_request_state,
|
||||
.stream = &DMA2_STREAM1_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = DIALOG_SPI_DMA_PRIORITY,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_compositor_dma_request_state;
|
||||
static DMARequest COMPOSITOR_DMA_REQUEST = {
|
||||
.state = &s_compositor_dma_request_state,
|
||||
.stream = &DMA2_STREAM2_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 11,
|
||||
.priority = DMARequestPriority_Medium,
|
||||
.type = DMARequestType_MemoryToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
DMARequest * const COMPOSITOR_DMA = &COMPOSITOR_DMA_REQUEST;
|
||||
|
||||
static DMARequestState s_dfsdm_dma_request_state;
|
||||
static DMARequest DFSDM_DMA_REQUEST = {
|
||||
.state = &s_dfsdm_dma_request_state,
|
||||
.stream = &DMA2_STREAM4_DEVICE,
|
||||
.channel = 8,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Word,
|
||||
};
|
||||
|
||||
static DMARequestState s_ice40lp_spi_tx_dma_request_state;
|
||||
static DMARequest ICE40LP_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_ice40lp_spi_tx_dma_request_state,
|
||||
.stream = &DMA2_STREAM5_DEVICE,
|
||||
.channel = 1,
|
||||
// Use the same priority as the EXTI handlers so that the DMA-complete
|
||||
// handler doesn't preempt the display BUSY (INTn) handler.
|
||||
.irq_priority = 0x0e,
|
||||
.priority = DMARequestPriority_Medium,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_qspi_dma_request_state;
|
||||
static DMARequest QSPI_DMA_REQUEST = {
|
||||
.state = &s_qspi_dma_request_state,
|
||||
.stream = &DMA2_STREAM7_DEVICE,
|
||||
.channel = 3,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Word,
|
||||
};
|
||||
|
||||
|
||||
// UART DEVICES
|
||||
|
||||
#if TARGET_QEMU
|
||||
static UARTDeviceState s_qemu_uart_state;
|
||||
static UARTDevice QEMU_UART_DEVICE = {
|
||||
.state = &s_qemu_uart_state,
|
||||
// GPIO? Where we're going, we don't need GPIO. (connected to QEMU)
|
||||
.periph = USART2,
|
||||
.irq_channel = USART2_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2
|
||||
};
|
||||
UARTDevice * const QEMU_UART = &QEMU_UART_DEVICE;
|
||||
IRQ_MAP(USART2, uart_irq_handler, QEMU_UART);
|
||||
#endif
|
||||
|
||||
static UARTDeviceState s_dbg_uart_state;
|
||||
static UARTDevice DBG_UART_DEVICE = {
|
||||
.state = &s_dbg_uart_state,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOD,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF7_USART3
|
||||
},
|
||||
.rx_gpio = {
|
||||
.gpio = GPIOD,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
.gpio_pin_source = GPIO_PinSource9,
|
||||
.gpio_af = GPIO_AF7_USART3
|
||||
},
|
||||
.periph = USART3,
|
||||
.irq_channel = USART3_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART3,
|
||||
.rx_dma = &DBG_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const DBG_UART = &DBG_UART_DEVICE;
|
||||
IRQ_MAP(USART3, uart_irq_handler, DBG_UART);
|
||||
|
||||
static UARTDeviceState s_accessory_uart_state;
|
||||
static UARTDevice ACCESSORY_UART_DEVICE = {
|
||||
.state = &s_accessory_uart_state,
|
||||
.half_duplex = true,
|
||||
.tx_gpio = {
|
||||
#if BOARD_ROBERT_BB || BOARD_CUTTS_BB
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_12,
|
||||
.gpio_pin_source = GPIO_PinSource12,
|
||||
.gpio_af = GPIO_AF6_UART4
|
||||
#elif BOARD_ROBERT_BB2 || BOARD_ROBERT_EVT
|
||||
.gpio = GPIOD,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
.gpio_pin_source = GPIO_PinSource1,
|
||||
.gpio_af = GPIO_AF8_UART4
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
},
|
||||
.periph = UART4,
|
||||
.irq_channel = UART4_IRQn,
|
||||
.irq_priority = 0xb,
|
||||
.rcc_apb_periph = RCC_APB1Periph_UART4,
|
||||
.rx_dma = &ACCESSORY_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const ACCESSORY_UART = &ACCESSORY_UART_DEVICE;
|
||||
IRQ_MAP(UART4, uart_irq_handler, ACCESSORY_UART);
|
||||
|
||||
static UARTDeviceState s_bt_bootrom_uart_state;
|
||||
static UARTDevice BT_BOOTROM_UART_DEVICE = {
|
||||
.state = &s_bt_bootrom_uart_state,
|
||||
#if BOARD_ROBERT_BB || BOARD_CUTTS_BB
|
||||
.do_swap_rx_tx = true,
|
||||
#elif BOARD_ROBERT_BB2 || BOARD_ROBERT_EVT
|
||||
.do_swap_rx_tx = false,
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
.rx_gpio = { GPIOE, GPIO_Pin_0, GPIO_PinSource0, GPIO_AF8_UART8 },
|
||||
.tx_gpio = { GPIOE, GPIO_Pin_1, GPIO_PinSource1, GPIO_AF8_UART8 },
|
||||
.rcc_apb_periph = RCC_APB1Periph_UART8,
|
||||
.periph = UART8,
|
||||
};
|
||||
|
||||
UARTDevice * const BT_TX_BOOTROM_UART = &BT_BOOTROM_UART_DEVICE;
|
||||
UARTDevice * const BT_RX_BOOTROM_UART = &BT_BOOTROM_UART_DEVICE;
|
||||
|
||||
// I2C DEVICES
|
||||
|
||||
#if BOARD_CUTTS_BB
|
||||
static I2CBusState I2C_TOUCH_ALS_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_TOUCH_ALS_BUS_HAL = {
|
||||
.i2c = I2C1,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C1,
|
||||
.bus_mode = I2CBusMode_FastMode,
|
||||
.clock_speed = 400000,
|
||||
// TODO: These need to be measured. Just using PMIC_MAG values for now.
|
||||
.rise_time_ns = 150,
|
||||
.fall_time_ns = 6,
|
||||
.ev_irq_channel = I2C1_EV_IRQn,
|
||||
.er_irq_channel = I2C1_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_TOUCH_ALS_BUS = {
|
||||
.state = &I2C_TOUCH_ALS_BUS_STATE,
|
||||
.hal = &I2C_TOUCH_ALS_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_6,
|
||||
.gpio_pin_source = GPIO_PinSource6,
|
||||
.gpio_af = GPIO_AF4_I2C1
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
.gpio_pin_source = GPIO_PinSource9,
|
||||
.gpio_af = GPIO_AF4_I2C1
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C1,
|
||||
.name = "I2C_TOUCH_ALS"
|
||||
};
|
||||
#endif
|
||||
|
||||
#if BOARD_CUTTS_BB
|
||||
static I2CBusState I2C_NFC_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_NFC_BUS_HAL = {
|
||||
.i2c = I2C3,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C3,
|
||||
.bus_mode = I2CBusMode_FastMode,
|
||||
.clock_speed = 400000,
|
||||
// TODO: These need to be measured. Just using PMIC_MAG values for now.
|
||||
.rise_time_ns = 150,
|
||||
.fall_time_ns = 6,
|
||||
.ev_irq_channel = I2C3_EV_IRQn,
|
||||
.er_irq_channel = I2C3_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_NFC_BUS = {
|
||||
.state = &I2C_NFC_BUS_STATE,
|
||||
.hal = &I2C_NFC_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF4_I2C3
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOH,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF4_I2C3
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C3,
|
||||
.name = "I2C_NFC"
|
||||
};
|
||||
#endif
|
||||
|
||||
static I2CBusState I2C_PMIC_MAG_BUS_STATE = {};
|
||||
static const I2CBusHal I2C_PMIC_MAG_BUS_HAL = {
|
||||
.i2c = I2C4,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C4,
|
||||
.bus_mode = I2CBusMode_FastMode,
|
||||
.clock_speed = 400000,
|
||||
#if BOARD_ROBERT_BB || BOARD_CUTTS_BB
|
||||
// These rise and fall times were measured.
|
||||
.rise_time_ns = 150,
|
||||
.fall_time_ns = 6,
|
||||
#elif BOARD_ROBERT_BB2
|
||||
// TODO: These rise and fall times are based on robert_bb and should be measured
|
||||
.rise_time_ns = 150,
|
||||
.fall_time_ns = 6,
|
||||
#elif BOARD_ROBERT_EVT
|
||||
// TODO: These are calculated and could potentially be measured.
|
||||
.rise_time_ns = 70,
|
||||
.fall_time_ns = 5,
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
.ev_irq_channel = I2C4_EV_IRQn,
|
||||
.er_irq_channel = I2C4_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_PMIC_MAG_BUS = {
|
||||
.state = &I2C_PMIC_MAG_BUS_STATE,
|
||||
.hal = &I2C_PMIC_MAG_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_14,
|
||||
.gpio_pin_source = GPIO_PinSource14,
|
||||
.gpio_af = GPIO_AF4_I2C4
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_15,
|
||||
.gpio_pin_source = GPIO_PinSource15,
|
||||
.gpio_af = GPIO_AF4_I2C4
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C4,
|
||||
.name = "I2C_PMIC_MAG"
|
||||
};
|
||||
|
||||
#if BOARD_CUTTS_BB
|
||||
static const I2CSlavePort I2C_SLAVE_EWD1000 = {
|
||||
.bus = &I2C_TOUCH_ALS_BUS,
|
||||
.address = 0x2A
|
||||
};
|
||||
#endif
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAX14690 = {
|
||||
.bus = &I2C_PMIC_MAG_BUS,
|
||||
.address = 0x50
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAG3110 = {
|
||||
.bus = &I2C_PMIC_MAG_BUS,
|
||||
.address = 0x0e << 1
|
||||
};
|
||||
|
||||
I2CSlavePort * const I2C_MAX14690 = &I2C_SLAVE_MAX14690;
|
||||
I2CSlavePort * const I2C_MAG3110 = &I2C_SLAVE_MAG3110;
|
||||
|
||||
IRQ_MAP(I2C4_EV, i2c_hal_event_irq_handler, &I2C_PMIC_MAG_BUS);
|
||||
IRQ_MAP(I2C4_ER, i2c_hal_error_irq_handler, &I2C_PMIC_MAG_BUS);
|
||||
#if BOARD_CUTTS_BB
|
||||
IRQ_MAP(I2C1_EV, i2c_hal_event_irq_handler, &I2C_TOUCH_ALS_BUS);
|
||||
IRQ_MAP(I2C1_ER, i2c_hal_error_irq_handler, &I2C_TOUCH_ALS_BUS);
|
||||
#endif
|
||||
|
||||
|
||||
#if BOARD_CUTTS_BB
|
||||
static const TouchSensor EWD1000_DEVICE = {
|
||||
.i2c = &I2C_SLAVE_EWD1000,
|
||||
.int_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
},
|
||||
.int_exti = {
|
||||
.exti_port_source = EXTI_PortSourceGPIOB,
|
||||
.exti_line = 7,
|
||||
},
|
||||
.reset_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_5,
|
||||
.active_high = true,
|
||||
},
|
||||
};
|
||||
|
||||
TouchSensor * const EWD1000 = &EWD1000_DEVICE;
|
||||
#endif
|
||||
|
||||
// VOLTAGE MONITOR DEVICES
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_ALS_DEVICE = {
|
||||
.adc = ADC3,
|
||||
.adc_channel = ADC_Channel_14,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC3,
|
||||
.input = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_4,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_BATTERY_DEVICE = {
|
||||
.adc = ADC1,
|
||||
.adc_channel = ADC_Channel_9,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC1,
|
||||
.input = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
}
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_TEMPERATURE_DEVICE = {
|
||||
.adc = ADC1,
|
||||
.adc_channel = ADC_Channel_TempSensor,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC1,
|
||||
// .input not applicable
|
||||
};
|
||||
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS = &VOLTAGE_MONITOR_ALS_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY = &VOLTAGE_MONITOR_BATTERY_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_TEMPERATURE = &VOLTAGE_MONITOR_TEMPERATURE_DEVICE;
|
||||
|
||||
|
||||
// Temperature sensor
|
||||
|
||||
const TemperatureSensor TEMPERATURE_SENSOR_DEVICE = {
|
||||
.voltage_monitor = &VOLTAGE_MONITOR_TEMPERATURE_DEVICE,
|
||||
.millivolts_ref = 760,
|
||||
.millidegrees_ref = 25000,
|
||||
.slope_numerator = 5,
|
||||
.slope_denominator = 2000,
|
||||
};
|
||||
const TemperatureSensor * const TEMPERATURE_SENSOR = &TEMPERATURE_SENSOR_DEVICE;
|
||||
|
||||
|
||||
//
|
||||
// SPI Bus configuration
|
||||
//
|
||||
|
||||
static SPIBusState DIALOG_SPI_BUS_STATE = { };
|
||||
static const SPIBus DIALOG_SPI_BUS = {
|
||||
.state = &DIALOG_SPI_BUS_STATE,
|
||||
.spi = SPI4,
|
||||
.spi_sclk = { GPIOE, GPIO_Pin_12, GPIO_PinSource12, GPIO_AF5_SPI5 },
|
||||
.spi_miso = { GPIOE, GPIO_Pin_13, GPIO_PinSource13, GPIO_AF5_SPI5 },
|
||||
.spi_mosi = { GPIOE, GPIO_Pin_14, GPIO_PinSource14, GPIO_AF5_SPI5 },
|
||||
.spi_sclk_speed = GPIO_Speed_50MHz,
|
||||
// DA14680_FS v1.4 page 89:
|
||||
// "In slave mode the internal SPI clock must be more than four times the SPIx_CLK"
|
||||
// The system clock is 16MHz, so don't use more than 4MHz.
|
||||
.spi_clock_speed_hz = MHZ_TO_HZ(4)
|
||||
};
|
||||
|
||||
static SPIBusState BMI160_SPI_BUS_STATE = {};
|
||||
static const SPIBus BMI160_SPI_BUS = {
|
||||
.state = &BMI160_SPI_BUS_STATE,
|
||||
.spi = SPI2,
|
||||
.spi_sclk = {
|
||||
.gpio = GPIOI,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
.gpio_pin_source = GPIO_PinSource1,
|
||||
.gpio_af = GPIO_AF5_SPI2
|
||||
},
|
||||
.spi_miso = {
|
||||
.gpio = GPIOI,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
.gpio_pin_source = GPIO_PinSource2,
|
||||
.gpio_af = GPIO_AF5_SPI2
|
||||
},
|
||||
.spi_mosi = {
|
||||
.gpio = GPIOI,
|
||||
.gpio_pin = GPIO_Pin_3,
|
||||
.gpio_pin_source = GPIO_PinSource3,
|
||||
.gpio_af = GPIO_AF5_SPI2
|
||||
},
|
||||
.spi_sclk_speed = GPIO_Speed_25MHz,
|
||||
.spi_clock_speed_hz = MHZ_TO_HZ(5),
|
||||
};
|
||||
|
||||
static SPIBusState ICE40LP_SPI_BUS_STATE = {};
|
||||
static const SPIBus ICE40LP_SPI_BUS = {
|
||||
.state = &ICE40LP_SPI_BUS_STATE,
|
||||
.spi = SPI6,
|
||||
.spi_sclk = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_5,
|
||||
.gpio_pin_source = GPIO_PinSource5,
|
||||
.gpio_af = GPIO_AF8_SPI6
|
||||
},
|
||||
.spi_miso = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_6,
|
||||
.gpio_pin_source = GPIO_PinSource6,
|
||||
.gpio_af = GPIO_AF8_SPI6
|
||||
},
|
||||
.spi_mosi = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF8_SPI6
|
||||
},
|
||||
.spi_sclk_speed = GPIO_Speed_25MHz,
|
||||
.spi_clock_speed_hz = MHZ_TO_HZ(16),
|
||||
};
|
||||
|
||||
//
|
||||
// SPI Slave port configuration
|
||||
//
|
||||
|
||||
static SPISlavePortState BMI160_SPI_SLAVE_PORT_STATE = {};
|
||||
static SPISlavePort BMI160_SPI_SLAVE_PORT = {
|
||||
.slave_state = &BMI160_SPI_SLAVE_PORT_STATE,
|
||||
.spi_bus = &BMI160_SPI_BUS,
|
||||
.spi_scs = {
|
||||
.gpio = GPIOI,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
.active_high = false
|
||||
},
|
||||
.spi_direction = SpiDirection_2LinesFullDuplex,
|
||||
.spi_cpol = SpiCPol_Low,
|
||||
.spi_cpha = SpiCPha_1Edge,
|
||||
.spi_first_bit = SpiFirstBit_MSB,
|
||||
};
|
||||
SPISlavePort * const BMI160_SPI = &BMI160_SPI_SLAVE_PORT;
|
||||
|
||||
static SPISlavePortState ICE40LP_SPI_SLAVE_PORT_STATE = {};
|
||||
static SPISlavePort ICE40LP_SPI_SLAVE_PORT = {
|
||||
.slave_state = &ICE40LP_SPI_SLAVE_PORT_STATE,
|
||||
.spi_bus = &ICE40LP_SPI_BUS,
|
||||
.spi_scs = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_4,
|
||||
.active_high = false
|
||||
},
|
||||
.spi_direction = SpiDirection_1LineTx,
|
||||
.spi_cpol = SpiCPol_High,
|
||||
.spi_cpha = SpiCPha_2Edge,
|
||||
.spi_first_bit = SpiFirstBit_MSB,
|
||||
.tx_dma = &ICE40LP_SPI_TX_DMA_REQUEST
|
||||
};
|
||||
|
||||
static SPISlavePortState DIALOG_SPI_SLAVE_PORT_STATE = {};
|
||||
static SPISlavePort DIALOG_SPI_SLAVE_PORT = {
|
||||
.slave_state = &DIALOG_SPI_SLAVE_PORT_STATE,
|
||||
.spi_bus = &DIALOG_SPI_BUS,
|
||||
.spi_scs = { GPIOE, GPIO_Pin_11, false },
|
||||
.spi_direction = SpiDirection_2LinesFullDuplex,
|
||||
.spi_cpol = SpiCPol_Low,
|
||||
.spi_cpha = SpiCPha_1Edge,
|
||||
.spi_first_bit = SpiFirstBit_MSB,
|
||||
.rx_dma = &DIALOG_SPI_RX_DMA_REQUEST,
|
||||
.tx_dma = &DIALOG_SPI_TX_DMA_REQUEST
|
||||
};
|
||||
SPISlavePort * const DIALOG_SPI = &DIALOG_SPI_SLAVE_PORT;
|
||||
|
||||
|
||||
|
||||
//
|
||||
// iCE40LP configuration
|
||||
//
|
||||
static ICE40LPDeviceState s_ice40lp_state;
|
||||
static ICE40LPDevice ICE40LP_DEVICE = {
|
||||
.state = &s_ice40lp_state,
|
||||
|
||||
.spi_port = &ICE40LP_SPI_SLAVE_PORT,
|
||||
.base_spi_frequency = MHZ_TO_HZ(16),
|
||||
.fast_spi_frequency = MHZ_TO_HZ(32),
|
||||
.creset = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_3,
|
||||
.active_high = true,
|
||||
},
|
||||
.cdone = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
},
|
||||
.busy = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
},
|
||||
.cdone_exti = {
|
||||
.exti_port_source = EXTI_PortSourceGPIOB,
|
||||
.exti_line = 2,
|
||||
},
|
||||
.busy_exti = {
|
||||
.exti_port_source = EXTI_PortSourceGPIOB,
|
||||
.exti_line = 0,
|
||||
},
|
||||
#if BOARD_CUTTS_BB
|
||||
.use_6v6_rail = true,
|
||||
#elif BOARD_ROBERT_BB || BOARD_ROBERT_BB2 || BOARD_ROBERT_EVT
|
||||
.use_6v6_rail = false,
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
};
|
||||
ICE40LPDevice * const ICE40LP = &ICE40LP_DEVICE;
|
||||
|
||||
|
||||
// QSPI
|
||||
static QSPIPortState s_qspi_port_state;
|
||||
static QSPIPort QSPI_PORT = {
|
||||
.state = &s_qspi_port_state,
|
||||
.clock_speed_hz = MHZ_TO_HZ(72),
|
||||
.auto_polling_interval = 16,
|
||||
.clock_ctrl = RCC_AHB3Periph_QSPI,
|
||||
.cs_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
.clk_gpio = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
.data_gpio = {
|
||||
{
|
||||
.gpio = GPIOD,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
{
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
{
|
||||
#if BOARD_ROBERT_BB || BOARD_ROBERT_BB2 || BOARD_CUTTS_BB
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
#elif BOARD_ROBERT_EVT
|
||||
.gpio = GPIOE,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
.gpio_pin_source = GPIO_PinSource2,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
},
|
||||
{
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
.gpio_pin_source = GPIO_PinSource1,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
},
|
||||
.dma = &QSPI_DMA_REQUEST,
|
||||
};
|
||||
QSPIPort * const QSPI = &QSPI_PORT;
|
||||
|
||||
static QSPIFlashState s_qspi_flash_state;
|
||||
static QSPIFlash QSPI_FLASH_DEVICE = {
|
||||
.state = &s_qspi_flash_state,
|
||||
.qspi = &QSPI_PORT,
|
||||
.default_fast_read_ddr_enabled = true,
|
||||
#if BOARD_ROBERT_BB || BOARD_ROBERT_BB2 || BOARD_CUTTS_BB
|
||||
.reset_gpio = { GPIO_Port_NULL },
|
||||
#elif BOARD_ROBERT_EVT
|
||||
.reset_gpio = {
|
||||
.gpio = GPIOE,
|
||||
.gpio_pin = GPIO_Pin_15,
|
||||
.active_high = false,
|
||||
},
|
||||
#else
|
||||
#error "Unknown error"
|
||||
#endif
|
||||
};
|
||||
QSPIFlash * const QSPI_FLASH = &QSPI_FLASH_DEVICE;
|
||||
|
||||
|
||||
void board_early_init(void) {
|
||||
spi_slave_port_init(ICE40LP->spi_port);
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
#if BOARD_CUTTS_BB
|
||||
i2c_init(&I2C_TOUCH_ALS_BUS);
|
||||
i2c_init(&I2C_NFC_BUS);
|
||||
#endif
|
||||
i2c_init(&I2C_PMIC_MAG_BUS);
|
||||
spi_slave_port_init(BMI160_SPI);
|
||||
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_ALS);
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_BATTERY);
|
||||
|
||||
qspi_init(QSPI, BOARD_NOR_FLASH_SIZE);
|
||||
}
|
310
src/fw/board/boards/board_robert.h
Normal file
310
src/fw/board/boards/board_robert.h
Normal file
|
@ -0,0 +1,310 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
// ----------------------------------------------
|
||||
// Board definitions for robert_bb, robert_bb2, robert_evt, cutts_bb
|
||||
// ----------------------------------------------
|
||||
//
|
||||
|
||||
#include "drivers/imu/bmi160/bmi160.h"
|
||||
#include "services/imu/units.h"
|
||||
#include "util/size.h"
|
||||
|
||||
#define BOARD_LSE_MODE RCC_LSE_Bypass
|
||||
|
||||
static const BoardConfig BOARD_CONFIG = {
|
||||
.ambient_light_dark_threshold = 3220,
|
||||
.ambient_k_delta_threshold = 96,
|
||||
.photo_en = { GPIOF, GPIO_Pin_5, true },
|
||||
.als_always_on = true,
|
||||
|
||||
.dbgserial_int = { EXTI_PortSourceGPIOH, 9 },
|
||||
.dbgserial_int_gpio = { GPIOH, GPIO_Pin_9 },
|
||||
|
||||
// Only used with Sharp displays
|
||||
.lcd_com = { 0 },
|
||||
|
||||
.power_5v0_options = OptionNotPresent,
|
||||
.power_ctl_5v0 = { 0 },
|
||||
|
||||
.backlight_on_percent = 45,
|
||||
.backlight_max_duty_cycle_percent = 100,
|
||||
|
||||
.num_avail_gpios = 140,
|
||||
|
||||
.has_mic = true,
|
||||
};
|
||||
|
||||
static const BoardConfigButton BOARD_CONFIG_BUTTON = {
|
||||
.buttons = {
|
||||
#if BOARD_ROBERT_BB || BOARD_CUTTS_BB || BOARD_ROBERT_BB2
|
||||
[BUTTON_ID_BACK] =
|
||||
{ "Back", GPIOG, GPIO_Pin_6, { EXTI_PortSourceGPIOG, 6 }, GPIO_PuPd_UP },
|
||||
[BUTTON_ID_UP] =
|
||||
{ "Up", GPIOG, GPIO_Pin_3, { EXTI_PortSourceGPIOG, 3 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_DOWN] =
|
||||
{ "Down", GPIOG, GPIO_Pin_4, { EXTI_PortSourceGPIOG, 4 }, GPIO_PuPd_UP },
|
||||
#elif BOARD_ROBERT_EVT
|
||||
[BUTTON_ID_BACK] =
|
||||
{ "Back", GPIOG, GPIO_Pin_3, { EXTI_PortSourceGPIOG, 3 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_UP] =
|
||||
{ "Up", GPIOG, GPIO_Pin_4, { EXTI_PortSourceGPIOG, 4 }, GPIO_PuPd_UP },
|
||||
[BUTTON_ID_DOWN] =
|
||||
{ "Down", GPIOG, GPIO_Pin_6, { EXTI_PortSourceGPIOG, 6 }, GPIO_PuPd_UP },
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
[BUTTON_ID_SELECT] =
|
||||
{ "Select", GPIOG, GPIO_Pin_5, { EXTI_PortSourceGPIOG, 5 }, GPIO_PuPd_UP },
|
||||
},
|
||||
|
||||
.button_com = { 0 },
|
||||
.active_high = false,
|
||||
};
|
||||
|
||||
static const BoardConfigPower BOARD_CONFIG_POWER = {
|
||||
.pmic_int = { EXTI_PortSourceGPIOF, 12 },
|
||||
.pmic_int_gpio = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_12,
|
||||
},
|
||||
|
||||
.rail_4V5_ctrl = {
|
||||
.gpio = GPIOH,
|
||||
.gpio_pin = GPIO_Pin_5,
|
||||
.active_high = true,
|
||||
},
|
||||
#if BOARD_CUTTS_BB
|
||||
.rail_6V6_ctrl = {
|
||||
.gpio = GPIOH,
|
||||
.gpio_pin = GPIO_Pin_3,
|
||||
.active_high = true,
|
||||
},
|
||||
.rail_6V6_ctrl_otype = GPIO_OType_PP,
|
||||
#elif BOARD_ROBERT_BB || BOARD_ROBERT_BB2 || BOARD_ROBERT_EVT
|
||||
.rail_6V6_ctrl = { GPIO_Port_NULL },
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
|
||||
.battery_vmon_scale = {
|
||||
// The PMIC divides the battery voltage by a ratio of 3:1 in order to move it down to a voltage
|
||||
// our ADC is capable of reading. The battery voltage varies around 4V~ and we're only capable
|
||||
// of reading up to 1.8V in the ADC.
|
||||
.numerator = 3,
|
||||
.denominator = 1,
|
||||
},
|
||||
|
||||
.vusb_stat = { .gpio = GPIO_Port_NULL, },
|
||||
.chg_stat = { GPIO_Port_NULL },
|
||||
.chg_fast = { GPIO_Port_NULL },
|
||||
.chg_en = { GPIO_Port_NULL },
|
||||
.has_vusb_interrupt = false,
|
||||
|
||||
.wake_on_usb_power = false,
|
||||
|
||||
#if defined(IS_BIGBOARD) && !defined(BATTERY_DEBUG)
|
||||
.charging_cutoff_voltage = 4200,
|
||||
#else
|
||||
.charging_cutoff_voltage = 4300,
|
||||
#endif
|
||||
.charging_status_led_voltage_compensation = 0,
|
||||
|
||||
.low_power_threshold = 2,
|
||||
.battery_capacity_hours = 204,
|
||||
};
|
||||
|
||||
static const BoardConfigAccel BOARD_CONFIG_ACCEL = {
|
||||
.accel_config = {
|
||||
.axes_offsets[AXIS_X] = 0,
|
||||
.axes_offsets[AXIS_Y] = 1,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
#if BOARD_ROBERT_BB || BOARD_ROBERT_BB2 || BOARD_CUTTS_BB
|
||||
.axes_inverts[AXIS_X] = true,
|
||||
.axes_inverts[AXIS_Y] = false,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
#elif BOARD_ROBERT_EVT
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = false,
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
.shake_thresholds[AccelThresholdHigh] = 0x64,
|
||||
.shake_thresholds[AccelThresholdLow] = 0xf,
|
||||
.double_tap_threshold = 12500,
|
||||
},
|
||||
.accel_int_gpios = {
|
||||
[0] = { GPIOH, GPIO_Pin_15 },
|
||||
[1] = { GPIOH, GPIO_Pin_14 },
|
||||
},
|
||||
.accel_ints = {
|
||||
[0] = { EXTI_PortSourceGPIOH, 15 },
|
||||
[1] = { EXTI_PortSourceGPIOH, 14 }
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMag BOARD_CONFIG_MAG = {
|
||||
.mag_config = {
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
#if BOARD_ROBERT_BB || BOARD_ROBERT_BB2 || BOARD_CUTTS_BB
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
#elif BOARD_ROBERT_EVT
|
||||
.axes_inverts[AXIS_X] = true,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = false,
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
},
|
||||
.mag_int_gpio = { GPIOF, GPIO_Pin_11 },
|
||||
.mag_int = { EXTI_PortSourceGPIOF, 11 },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_VIBE = {
|
||||
.options = ActuatorOptions_Ctl | ActuatorOptions_Pwm | ActuatorOptions_HBridge,
|
||||
#if BOARD_ROBERT_BB || BOARD_CUTTS_BB
|
||||
.ctl = { GPIOD, GPIO_Pin_14, true },
|
||||
.pwm = {
|
||||
.output = { GPIOD, GPIO_Pin_12, true },
|
||||
.timer = {
|
||||
.peripheral = TIM4,
|
||||
.config_clock = RCC_APB1Periph_TIM4,
|
||||
.init = TIM_OC1Init,
|
||||
.preload = TIM_OC1PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOD, GPIO_Pin_12, GPIO_PinSource12, GPIO_AF2_TIM4 },
|
||||
},
|
||||
#elif BOARD_ROBERT_BB2 || BOARD_ROBERT_EVT
|
||||
.ctl = { GPIOA, GPIO_Pin_12, true },
|
||||
.pwm = {
|
||||
.output = { GPIOB, GPIO_Pin_14, true },
|
||||
.timer = {
|
||||
.peripheral = TIM12,
|
||||
.config_clock = RCC_APB1Periph_TIM12,
|
||||
.init = TIM_OC1Init,
|
||||
.preload = TIM_OC1PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOB, GPIO_Pin_14, GPIO_PinSource14, GPIO_AF9_TIM12 },
|
||||
},
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_BACKLIGHT = {
|
||||
.options = ActuatorOptions_Pwm,
|
||||
.ctl = {0},
|
||||
.pwm = {
|
||||
.output = { GPIOG, GPIO_Pin_13, true },
|
||||
.timer = {
|
||||
.lp_peripheral = LPTIM1,
|
||||
.config_clock = RCC_APB1Periph_LPTIM1,
|
||||
},
|
||||
.afcfg = { GPIOG, GPIO_Pin_13, GPIO_PinSource13, GPIO_AF3_LPTIM1 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigAccessory BOARD_CONFIG_ACCESSORY = {
|
||||
#if BOARD_ROBERT_BB || BOARD_CUTTS_BB
|
||||
.power_en = { GPIOA, GPIO_Pin_11, true },
|
||||
#elif BOARD_ROBERT_BB2 || BOARD_ROBERT_EVT
|
||||
.power_en = { GPIOD, GPIO_Pin_2, true },
|
||||
#else
|
||||
#error "Unknown board"
|
||||
#endif
|
||||
.int_gpio = { GPIOH, GPIO_Pin_13 },
|
||||
.exti = { EXTI_PortSourceGPIOH, 13 },
|
||||
};
|
||||
|
||||
static const BoardConfigBTCommon BOARD_CONFIG_BT_COMMON = {
|
||||
.controller = DA14681,
|
||||
.reset = { GPIOG, GPIO_Pin_0, true },
|
||||
.wakeup = {
|
||||
.int_gpio = { GPIOG, GPIO_Pin_1 },
|
||||
.int_exti = { EXTI_PortSourceGPIOG, 1 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigBTUART BOARD_CONFIG_BT_UART = {
|
||||
.rx_af_cfg = { GPIOE, GPIO_Pin_0, GPIO_PinSource0, GPIO_AF8_UART8 },
|
||||
.tx_af_cfg = { GPIOE, GPIO_Pin_1, GPIO_PinSource1, GPIO_AF8_UART8 },
|
||||
.rx_clk_control = RCC_APB1Periph_UART8,
|
||||
.tx_clk_control = RCC_APB1Periph_UART8,
|
||||
.rx_uart = UART8,
|
||||
.tx_uart = UART8,
|
||||
};
|
||||
|
||||
static const BoardConfigBTSPI BOARD_CONFIG_BT_SPI = {
|
||||
.cs = { GPIOE, GPIO_Pin_11, false },
|
||||
};
|
||||
|
||||
static const BoardConfigMCO1 BOARD_CONFIG_MCO1 = {
|
||||
.output_enabled = true,
|
||||
.af_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF0_MCO,
|
||||
},
|
||||
.an_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
},
|
||||
};
|
||||
|
||||
#define DIALOG_TIMER_IRQ_HANDLER TIM6_DAC_IRQHandler
|
||||
static const TimerIrqConfig BOARD_BT_WATCHDOG_TIMER = {
|
||||
.timer = {
|
||||
.peripheral = TIM6,
|
||||
.config_clock = RCC_APB1Periph_TIM6,
|
||||
},
|
||||
.irq_channel = TIM6_DAC_IRQn,
|
||||
};
|
||||
|
||||
extern DMARequest * const COMPOSITOR_DMA;
|
||||
|
||||
extern UARTDevice * const QEMU_UART;
|
||||
extern UARTDevice * const DBG_UART;
|
||||
extern UARTDevice * const ACCESSORY_UART;
|
||||
extern UARTDevice * const BT_TX_BOOTROM_UART;
|
||||
extern UARTDevice * const BT_RX_BOOTROM_UART;
|
||||
|
||||
extern SPISlavePort * const BMI160_SPI;
|
||||
|
||||
extern I2CSlavePort * const I2C_MAX14690;
|
||||
extern I2CSlavePort * const I2C_MAG3110;
|
||||
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS;
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY;
|
||||
|
||||
extern TemperatureSensor * const TEMPERATURE_SENSOR;
|
||||
|
||||
extern QSPIPort * const QSPI;
|
||||
extern QSPIFlash * const QSPI_FLASH;
|
||||
|
||||
extern ICE40LPDevice * const ICE40LP;
|
||||
extern SPISlavePort * const DIALOG_SPI;
|
||||
|
||||
#if BOARD_CUTTS_BB
|
||||
extern TouchSensor * const EWD1000;
|
||||
#endif
|
427
src/fw/board/boards/board_silk.c
Normal file
427
src/fw/board/boards/board_silk.c
Normal file
|
@ -0,0 +1,427 @@
|
|||
/*
|
||||
* 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/exti.h"
|
||||
#include "drivers/flash/qspi_flash_definitions.h"
|
||||
#include "drivers/i2c_definitions.h"
|
||||
#include "drivers/qspi_definitions.h"
|
||||
#include "drivers/stm32f2/dma_definitions.h"
|
||||
#include "drivers/stm32f2/i2c_hal_definitions.h"
|
||||
#include "drivers/stm32f2/spi_definitions.h"
|
||||
#include "drivers/stm32f2/uart_definitions.h"
|
||||
#include "drivers/temperature.h"
|
||||
#include "drivers/voltage_monitor.h"
|
||||
#include "flash_region/flash_region.h"
|
||||
#include "util/units.h"
|
||||
|
||||
#define DIALOG_SPI_DMA_PRIORITY (0x0b)
|
||||
// Make sure that the DMA IRQ is handled before EXTI:
|
||||
// See comments in host/host_transport.c prv_int_exti_cb()
|
||||
_Static_assert(DIALOG_SPI_DMA_PRIORITY < EXTI_PRIORITY, "Dialog SPI DMA priority too low!");
|
||||
|
||||
// DMA Controllers
|
||||
|
||||
static DMAControllerState s_dma1_state;
|
||||
static DMAController DMA1_DEVICE = {
|
||||
.state = &s_dma1_state,
|
||||
.periph = DMA1,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA1,
|
||||
};
|
||||
|
||||
static DMAControllerState s_dma2_state;
|
||||
static DMAController DMA2_DEVICE = {
|
||||
.state = &s_dma2_state,
|
||||
.periph = DMA2,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA2,
|
||||
};
|
||||
|
||||
// DMA Streams
|
||||
|
||||
CREATE_DMA_STREAM(1, 4); // DMA2_STREAM2_DEVICE - Sharp SPI TX
|
||||
CREATE_DMA_STREAM(2, 1); // DMA1_STREAM2_DEVICE - Accessory UART RX
|
||||
CREATE_DMA_STREAM(2, 2); // DMA1_STREAM1_DEVICE - Debug UART RX
|
||||
CREATE_DMA_STREAM(2, 3); // DMA2_STREAM0_DEVICE - Dialog SPI RX
|
||||
CREATE_DMA_STREAM(2, 5); // DMA2_STREAM1_DEVICE - Dialog SPI TX
|
||||
CREATE_DMA_STREAM(2, 6); // DMA2_STREAM4_DEVICE - DFSDM
|
||||
CREATE_DMA_STREAM(2, 7); // DMA2_STREAM7_DEVICE - QSPI
|
||||
|
||||
// DMA Requests
|
||||
// - On DMA1 we just have have "Sharp SPI TX" so just set its priority to "High" since it doesn't
|
||||
// matter.
|
||||
// - On DMA2 we have "Accessory UART RX", "Debug UART RX", "Dialog SPI RX", "DIALOG SPI TX",
|
||||
// "DFSDM", and "QSPI". We want "DFSDM", "Accessory UART RX", "Debug UART RX", and "Dialog SPI RX"
|
||||
// to have a very high priority because their peripheral buffers may overflow if the DMA stream
|
||||
// doesn't read from them in a while. After that, give the remaining "Dialog SPI TX" and "QSPI"
|
||||
// both a high priority.
|
||||
|
||||
static DMARequestState s_sharp_spi_tx_dma_request_state;
|
||||
static DMARequest SHARP_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_sharp_spi_tx_dma_request_state,
|
||||
.stream = &DMA1_STREAM4_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
DMARequest * const SHARP_SPI_TX_DMA = &SHARP_SPI_TX_DMA_REQUEST;
|
||||
|
||||
static DMARequestState s_accessory_uart_dma_request_state;
|
||||
static DMARequest ACCESSORY_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_accessory_uart_dma_request_state,
|
||||
.stream = &DMA2_STREAM1_DEVICE,
|
||||
.channel = 5,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_dbg_uart_dma_request_state;
|
||||
static DMARequest DBG_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_dbg_uart_dma_request_state,
|
||||
.stream = &DMA2_STREAM2_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_dialog_spi_rx_dma_request_state;
|
||||
static DMARequest DIALOG_SPI_RX_DMA_REQUEST = {
|
||||
.state = &s_dialog_spi_rx_dma_request_state,
|
||||
.stream = &DMA2_STREAM3_DEVICE,
|
||||
.channel = 2,
|
||||
.irq_priority = DIALOG_SPI_DMA_PRIORITY,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_dialog_spi_tx_dma_request_state;
|
||||
static DMARequest DIALOG_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_dialog_spi_tx_dma_request_state,
|
||||
.stream = &DMA2_STREAM5_DEVICE,
|
||||
.channel = 5,
|
||||
.irq_priority = DIALOG_SPI_DMA_PRIORITY,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_dfsdm_dma_request_state;
|
||||
static DMARequest DFSDM_DMA_REQUEST = {
|
||||
.state = &s_dfsdm_dma_request_state,
|
||||
.stream = &DMA2_STREAM6_DEVICE,
|
||||
.channel = 3,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Word,
|
||||
};
|
||||
|
||||
static DMARequestState s_qspi_dma_request_state;
|
||||
static DMARequest QSPI_DMA_REQUEST = {
|
||||
.state = &s_qspi_dma_request_state,
|
||||
.stream = &DMA2_STREAM7_DEVICE,
|
||||
.channel = 3,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Word,
|
||||
};
|
||||
|
||||
|
||||
// UART DEVICES
|
||||
|
||||
static UARTDeviceState s_bt_bootrom_rx_uart_state;
|
||||
static UARTDevice BT_RX_BOOTROM_UART_DEVICE = {
|
||||
.state = &s_bt_bootrom_rx_uart_state,
|
||||
.periph = USART6,
|
||||
.rx_gpio = { GPIOA, GPIO_Pin_12, GPIO_PinSource12, GPIO_AF_USART6 },
|
||||
.rcc_apb_periph = RCC_APB2Periph_USART6,
|
||||
.tx_gpio = { 0 }
|
||||
};
|
||||
|
||||
static UARTDeviceState s_bt_bootrom_tx_uart_state;
|
||||
static UARTDevice BT_TX_BOOTROM_UART_DEVICE = {
|
||||
.state = &s_bt_bootrom_tx_uart_state,
|
||||
.periph = USART2,
|
||||
.tx_gpio = { GPIOA, GPIO_Pin_2, GPIO_PinSource2, GPIO_AF_USART2 },
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2,
|
||||
.rx_gpio = { 0 }
|
||||
};
|
||||
|
||||
UARTDevice * const BT_TX_BOOTROM_UART = &BT_TX_BOOTROM_UART_DEVICE;
|
||||
UARTDevice * const BT_RX_BOOTROM_UART = &BT_RX_BOOTROM_UART_DEVICE;
|
||||
|
||||
#if TARGET_QEMU
|
||||
static UARTDeviceState s_qemu_uart_state;
|
||||
static UARTDevice QEMU_UART_DEVICE = {
|
||||
.state = &s_qemu_uart_state,
|
||||
// GPIO? Where we're going, we don't need GPIO. (connected to QEMU)
|
||||
.periph = USART2,
|
||||
.irq_channel = USART2_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2
|
||||
};
|
||||
UARTDevice * const QEMU_UART = &QEMU_UART_DEVICE;
|
||||
IRQ_MAP(USART2, uart_irq_handler, QEMU_UART);
|
||||
#endif
|
||||
|
||||
static UARTDeviceState s_dbg_uart_state;
|
||||
static UARTDevice DBG_UART_DEVICE = {
|
||||
.state = &s_dbg_uart_state,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
.gpio_pin_source = GPIO_PinSource9,
|
||||
.gpio_af = GPIO_AF_USART1
|
||||
},
|
||||
.rx_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF_USART1
|
||||
},
|
||||
.periph = USART1,
|
||||
.irq_channel = USART1_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB2Periph_USART1,
|
||||
.rx_dma = &DBG_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const DBG_UART = &DBG_UART_DEVICE;
|
||||
IRQ_MAP(USART1, uart_irq_handler, DBG_UART);
|
||||
|
||||
static UARTDeviceState s_accessory_uart_state;
|
||||
static UARTDevice ACCESSORY_UART_DEVICE = {
|
||||
.state = &s_accessory_uart_state,
|
||||
.half_duplex = true,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_USART6
|
||||
},
|
||||
.periph = USART6,
|
||||
.irq_channel = USART6_IRQn,
|
||||
.irq_priority = 0xb,
|
||||
.rcc_apb_periph = RCC_APB2Periph_USART6,
|
||||
.rx_dma = &ACCESSORY_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const ACCESSORY_UART = &ACCESSORY_UART_DEVICE;
|
||||
IRQ_MAP(USART6, uart_irq_handler, ACCESSORY_UART);
|
||||
|
||||
|
||||
// I2C DEVICES
|
||||
|
||||
static I2CBusState I2C_PMIC_HRM_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_PMIC_HRM_BUS_HAL = {
|
||||
.i2c = I2C3,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C3,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_2,
|
||||
.ev_irq_channel = I2C3_EV_IRQn,
|
||||
.er_irq_channel = I2C3_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_PMIC_HRM_BUS = {
|
||||
.state = &I2C_PMIC_HRM_BUS_STATE,
|
||||
.hal = &I2C_PMIC_HRM_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_I2C3
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF9_I2C3
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C3,
|
||||
.name = "I2C_PMIC"
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_AS3701B = {
|
||||
.bus = &I2C_PMIC_HRM_BUS,
|
||||
.address = 0x80
|
||||
};
|
||||
|
||||
I2CSlavePort * const I2C_AS3701B = &I2C_SLAVE_AS3701B;
|
||||
|
||||
IRQ_MAP(I2C3_EV, i2c_hal_event_irq_handler, &I2C_PMIC_HRM_BUS);
|
||||
IRQ_MAP(I2C3_ER, i2c_hal_error_irq_handler, &I2C_PMIC_HRM_BUS);
|
||||
|
||||
|
||||
// VOLTAGE MONITOR DEVICES
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_ALS_DEVICE = {
|
||||
.adc = ADC1,
|
||||
.adc_channel = ADC_Channel_13,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC1,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_3,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_BATTERY_DEVICE = {
|
||||
.adc = ADC1,
|
||||
.adc_channel = ADC_Channel_5,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC1,
|
||||
.input = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_5,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_TEMPERATURE_DEVICE = {
|
||||
.adc = ADC1,
|
||||
.adc_channel = ADC_Channel_TempSensor,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC1,
|
||||
// .input not applicable
|
||||
};
|
||||
|
||||
const VoltageMonitorDevice * VOLTAGE_MONITOR_ALS = &VOLTAGE_MONITOR_ALS_DEVICE;
|
||||
const VoltageMonitorDevice * VOLTAGE_MONITOR_BATTERY = &VOLTAGE_MONITOR_BATTERY_DEVICE;
|
||||
const VoltageMonitorDevice * VOLTAGE_MONITOR_TEMPERATURE = &VOLTAGE_MONITOR_TEMPERATURE_DEVICE;
|
||||
|
||||
// Temperature sensor
|
||||
// STM32F412 datasheet rev 2
|
||||
// Section 6.3.21
|
||||
TemperatureSensor const TEMPERATURE_SENSOR_DEVICE = {
|
||||
.voltage_monitor = &VOLTAGE_MONITOR_TEMPERATURE_DEVICE,
|
||||
.millivolts_ref = 760,
|
||||
.millidegrees_ref = 25000,
|
||||
.slope_numerator = 5,
|
||||
.slope_denominator = 2000,
|
||||
};
|
||||
|
||||
TemperatureSensor * const TEMPERATURE_SENSOR = &TEMPERATURE_SENSOR_DEVICE;
|
||||
|
||||
|
||||
//
|
||||
// SPI Bus configuration
|
||||
//
|
||||
|
||||
static SPIBusState DIALOG_SPI_BUS_STATE = { };
|
||||
static const SPIBus DIALOG_SPI_BUS = {
|
||||
.state = &DIALOG_SPI_BUS_STATE,
|
||||
.spi = SPI5,
|
||||
.spi_sclk = { GPIOB, GPIO_Pin_0, GPIO_PinSource0, GPIO_AF6_SPI5 },
|
||||
.spi_miso = { GPIOA, GPIO_Pin_12, GPIO_PinSource12, GPIO_AF6_SPI5 },
|
||||
.spi_mosi = { GPIOA, GPIO_Pin_10, GPIO_PinSource10, GPIO_AF6_SPI5 },
|
||||
.spi_sclk_speed = GPIO_Speed_50MHz,
|
||||
// DA14680_FS v1.4 page 89:
|
||||
// "In slave mode the internal SPI clock must be more than four times the SPIx_CLK"
|
||||
// The system clock is 16MHz, so don't use more than 4MHz.
|
||||
.spi_clock_speed_hz = MHZ_TO_HZ(4)
|
||||
};
|
||||
|
||||
//
|
||||
// SPI Slave port configuration
|
||||
//
|
||||
|
||||
static SPISlavePortState DIALOG_SPI_SLAVE_PORT_STATE = {};
|
||||
static SPISlavePort DIALOG_SPI_SLAVE_PORT = {
|
||||
.slave_state = &DIALOG_SPI_SLAVE_PORT_STATE,
|
||||
.spi_bus = &DIALOG_SPI_BUS,
|
||||
.spi_scs = { GPIOB, GPIO_Pin_1, false },
|
||||
.spi_direction = SpiDirection_2LinesFullDuplex,
|
||||
.spi_cpol = SpiCPol_Low,
|
||||
.spi_cpha = SpiCPha_1Edge,
|
||||
.spi_first_bit = SpiFirstBit_MSB,
|
||||
.rx_dma = &DIALOG_SPI_RX_DMA_REQUEST,
|
||||
.tx_dma = &DIALOG_SPI_TX_DMA_REQUEST
|
||||
};
|
||||
SPISlavePort * const DIALOG_SPI = &DIALOG_SPI_SLAVE_PORT;
|
||||
|
||||
|
||||
// QSPI
|
||||
static QSPIPortState s_qspi_port_state;
|
||||
static QSPIPort QSPI_PORT = {
|
||||
.state = &s_qspi_port_state,
|
||||
.clock_speed_hz = MHZ_TO_HZ(50),
|
||||
.auto_polling_interval = 16,
|
||||
.clock_ctrl = RCC_AHB3Periph_QSPI,
|
||||
.cs_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_6,
|
||||
.gpio_pin_source = GPIO_PinSource6,
|
||||
.gpio_af = GPIO_AF10_QUADSPI,
|
||||
},
|
||||
.clk_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
.gpio_pin_source = GPIO_PinSource2,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
.data_gpio = {
|
||||
{
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
.gpio_pin_source = GPIO_PinSource9,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
{
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
{
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
{
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
.gpio_pin_source = GPIO_PinSource1,
|
||||
.gpio_af = GPIO_AF9_QUADSPI,
|
||||
},
|
||||
},
|
||||
.dma = &QSPI_DMA_REQUEST,
|
||||
};
|
||||
QSPIPort * const QSPI = &QSPI_PORT;
|
||||
|
||||
static QSPIFlashState s_qspi_flash_state;
|
||||
static QSPIFlash QSPI_FLASH_DEVICE = {
|
||||
.state = &s_qspi_flash_state,
|
||||
.qspi = &QSPI_PORT,
|
||||
.default_fast_read_ddr_enabled = false,
|
||||
.reset_gpio = { GPIO_Port_NULL },
|
||||
};
|
||||
QSPIFlash * const QSPI_FLASH = &QSPI_FLASH_DEVICE;
|
||||
|
||||
|
||||
void board_early_init(void) {
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
i2c_init(&I2C_PMIC_HRM_BUS);
|
||||
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_ALS);
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_BATTERY);
|
||||
|
||||
qspi_init(QSPI, BOARD_NOR_FLASH_SIZE);
|
||||
}
|
241
src/fw/board/boards/board_silk.h
Normal file
241
src/fw/board/boards/board_silk.h
Normal 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.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "services/imu/units.h"
|
||||
#include "util/size.h"
|
||||
|
||||
#define BOARD_LSE_MODE RCC_LSE_Bypass
|
||||
|
||||
static const BoardConfig BOARD_CONFIG = {
|
||||
.ambient_light_dark_threshold = 150,
|
||||
.ambient_k_delta_threshold = 50,
|
||||
.photo_en = { GPIOC, GPIO_Pin_0, true },
|
||||
.als_always_on = true,
|
||||
|
||||
.dbgserial_int = { EXTI_PortSourceGPIOB, 5 },
|
||||
|
||||
// new sharp display requires 30/60Hz so we feed it directly from PMIC
|
||||
.lcd_com = { 0 },
|
||||
|
||||
.backlight_on_percent = 25,
|
||||
.backlight_max_duty_cycle_percent = 67,
|
||||
|
||||
.power_5v0_options = OptionNotPresent,
|
||||
.power_ctl_5v0 = { 0 },
|
||||
|
||||
.has_mic = true,
|
||||
};
|
||||
|
||||
static const BoardConfigButton BOARD_CONFIG_BUTTON = {
|
||||
.buttons = {
|
||||
[BUTTON_ID_BACK] =
|
||||
{ "Back", GPIOC, GPIO_Pin_13, { EXTI_PortSourceGPIOC, 13 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_UP] =
|
||||
{ "Up", GPIOD, GPIO_Pin_2, { EXTI_PortSourceGPIOD, 2 }, GPIO_PuPd_DOWN },
|
||||
[BUTTON_ID_SELECT] =
|
||||
{ "Select", GPIOH, GPIO_Pin_0, { EXTI_PortSourceGPIOH, 0 }, GPIO_PuPd_DOWN },
|
||||
[BUTTON_ID_DOWN] =
|
||||
{ "Down", GPIOH, GPIO_Pin_1, { EXTI_PortSourceGPIOH, 1 }, GPIO_PuPd_DOWN },
|
||||
},
|
||||
.button_com = { 0 },
|
||||
.active_high = true,
|
||||
};
|
||||
|
||||
static const BoardConfigPower BOARD_CONFIG_POWER = {
|
||||
.pmic_int = { EXTI_PortSourceGPIOC, 7 },
|
||||
.pmic_int_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
},
|
||||
|
||||
.battery_vmon_scale = {
|
||||
// Battery voltage is scaled down by a pair of resistors:
|
||||
// - R13 on the top @ 47k
|
||||
// - R15 on the bottom @ 30.1k
|
||||
// (R13 + R15) / R15 = 77.1 / 30.1
|
||||
.numerator = 771,
|
||||
.denominator = 301,
|
||||
},
|
||||
|
||||
.vusb_stat = { .gpio = GPIO_Port_NULL, },
|
||||
.chg_stat = { GPIO_Port_NULL },
|
||||
.chg_fast = { GPIO_Port_NULL },
|
||||
.chg_en = { GPIO_Port_NULL },
|
||||
.has_vusb_interrupt = false,
|
||||
|
||||
.wake_on_usb_power = false,
|
||||
|
||||
.charging_status_led_voltage_compensation = 0,
|
||||
|
||||
#if defined(IS_BIGBOARD) && !defined(BATTERY_DEBUG)
|
||||
// We don't use the same batteries on all bigboards, so set a safe cutoff voltage of 4.2V.
|
||||
// Please do not change this!
|
||||
.charging_cutoff_voltage = 4200,
|
||||
#else
|
||||
.charging_cutoff_voltage = 4300,
|
||||
#endif
|
||||
|
||||
.low_power_threshold = 5,
|
||||
|
||||
// Based on measurements from v4.0-beta16.
|
||||
// Typical Connected Current at VBAT without HRM ~520uA
|
||||
// Added draw with HRM on : ~1.5mA ==> Average impact (5% per hour + 1 hour continuous / day)
|
||||
// (.05 * 23/24 + 1.0 * 1/24) * 1.5mA = ~134uA
|
||||
// Assume ~150uA or so for notifications & user interaction
|
||||
// Total Hours = 125 mA * hr / (.520 + .134 + 150)mA = 155 hours
|
||||
.battery_capacity_hours = 155,
|
||||
};
|
||||
|
||||
static const BoardConfigAccel BOARD_CONFIG_ACCEL = {
|
||||
.accel_config = {
|
||||
.axes_offsets[AXIS_X] = 0,
|
||||
.axes_offsets[AXIS_Y] = 1,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
#if IS_BIGBOARD
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = false,
|
||||
.axes_inverts[AXIS_Z] = false,
|
||||
#else
|
||||
.axes_inverts[AXIS_X] = true,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
#endif
|
||||
// This is affected by the acceleromter's configured ODR, so this value
|
||||
// will need to be tuned again once we stop locking the BMA255 to an ODR of
|
||||
// 125 Hz.
|
||||
.shake_thresholds[AccelThresholdHigh] = 64,
|
||||
.shake_thresholds[AccelThresholdLow] = 0xf,
|
||||
.double_tap_threshold = 12500,
|
||||
},
|
||||
.accel_int_gpios = {
|
||||
[0] = { GPIOA, GPIO_Pin_6 },
|
||||
[1] = { GPIOA, GPIO_Pin_3 },
|
||||
},
|
||||
.accel_ints = {
|
||||
[0] = { EXTI_PortSourceGPIOA, 6 },
|
||||
[1] = { EXTI_PortSourceGPIOA, 3 }
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_VIBE = {
|
||||
.options = ActuatorOptions_Pwm,
|
||||
.ctl = { 0 },
|
||||
.pwm = {
|
||||
.output = { GPIOA, GPIO_Pin_7, true },
|
||||
.timer = {
|
||||
.peripheral = TIM14,
|
||||
.config_clock = RCC_APB1Periph_TIM14,
|
||||
.init = TIM_OC1Init,
|
||||
.preload = TIM_OC1PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOA, GPIO_Pin_7, GPIO_PinSource7, GPIO_AF_TIM14 },
|
||||
},
|
||||
.vsys_scale = 3300,
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_BACKLIGHT = {
|
||||
.options = ActuatorOptions_Pwm | ActuatorOptions_Ctl,
|
||||
.ctl = { GPIOB, GPIO_Pin_13, true },
|
||||
.pwm = {
|
||||
.output = { GPIOC, GPIO_Pin_6, true },
|
||||
.timer = {
|
||||
.peripheral = TIM3,
|
||||
.config_clock = RCC_APB1Periph_TIM3,
|
||||
.init = TIM_OC1Init,
|
||||
.preload = TIM_OC1PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOC, GPIO_Pin_6, GPIO_PinSource6, GPIO_AF_TIM3 },
|
||||
},
|
||||
};
|
||||
|
||||
#define ACCESSORY_UART_IS_SHARED_WITH_BT 1
|
||||
static const BoardConfigAccessory BOARD_CONFIG_ACCESSORY = {
|
||||
.exti = { EXTI_PortSourceGPIOA, 11 },
|
||||
};
|
||||
|
||||
static const BoardConfigBTCommon BOARD_CONFIG_BT_COMMON = {
|
||||
.controller = DA14681,
|
||||
.reset = { GPIOC, GPIO_Pin_5, true },
|
||||
.wakeup = {
|
||||
.int_gpio = { GPIOC, GPIO_Pin_4 },
|
||||
.int_exti = { EXTI_PortSourceGPIOC, 4 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigBTSPI BOARD_CONFIG_BT_SPI = {
|
||||
.cs = { GPIOB, GPIO_Pin_1, false },
|
||||
};
|
||||
|
||||
static const BoardConfigMCO1 BOARD_CONFIG_MCO1 = {
|
||||
.output_enabled = true,
|
||||
.af_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_MCO,
|
||||
},
|
||||
.an_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigSharpDisplay BOARD_CONFIG_DISPLAY = {
|
||||
.spi = SPI2,
|
||||
.spi_gpio = GPIOB,
|
||||
.spi_clk = RCC_APB1Periph_SPI2,
|
||||
.spi_clk_periph = SpiPeriphClockAPB1,
|
||||
|
||||
.clk = { GPIOB, GPIO_Pin_10, GPIO_PinSource10, GPIO_AF_SPI2 },
|
||||
.mosi = { GPIOB, GPIO_Pin_15, GPIO_PinSource15, GPIO_AF_SPI2 },
|
||||
.cs = { GPIOB, GPIO_Pin_9, true },
|
||||
|
||||
.on_ctrl = { GPIOA, GPIO_Pin_0, true },
|
||||
.on_ctrl_otype = GPIO_OType_PP,
|
||||
};
|
||||
|
||||
#define DIALOG_TIMER_IRQ_HANDLER TIM6_IRQHandler
|
||||
static const TimerIrqConfig BOARD_BT_WATCHDOG_TIMER = {
|
||||
.timer = {
|
||||
.peripheral = TIM6,
|
||||
.config_clock = RCC_APB1Periph_TIM6,
|
||||
},
|
||||
.irq_channel = TIM6_IRQn,
|
||||
};
|
||||
|
||||
extern DMARequest * const COMPOSITOR_DMA;
|
||||
extern DMARequest * const SHARP_SPI_TX_DMA;
|
||||
|
||||
extern UARTDevice * const QEMU_UART;
|
||||
extern UARTDevice * const DBG_UART;
|
||||
extern UARTDevice * const ACCESSORY_UART;
|
||||
|
||||
extern UARTDevice * const BT_TX_BOOTROM_UART;
|
||||
extern UARTDevice * const BT_RX_BOOTROM_UART;
|
||||
|
||||
extern I2CSlavePort * const I2C_AS3701B;
|
||||
|
||||
extern const VoltageMonitorDevice * VOLTAGE_MONITOR_ALS;
|
||||
extern const VoltageMonitorDevice * VOLTAGE_MONITOR_BATTERY;
|
||||
|
||||
extern const TemperatureSensor * const TEMPERATURE_SENSOR;
|
||||
|
||||
extern QSPIPort * const QSPI;
|
||||
extern QSPIFlash * const QSPI_FLASH;
|
||||
|
||||
extern SPISlavePort * const DIALOG_SPI;
|
449
src/fw/board/boards/board_snowy.c
Normal file
449
src/fw/board/boards/board_snowy.c
Normal file
|
@ -0,0 +1,449 @@
|
|||
/*
|
||||
* 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/display/ice40lp/ice40lp_definitions.h"
|
||||
#include "drivers/i2c_definitions.h"
|
||||
#include "drivers/stm32f2/dma_definitions.h"
|
||||
#include "drivers/stm32f2/i2c_hal_definitions.h"
|
||||
#include "drivers/stm32f2/spi_definitions.h"
|
||||
#include "drivers/stm32f2/uart_definitions.h"
|
||||
#include "drivers/temperature.h"
|
||||
#include "drivers/voltage_monitor.h"
|
||||
#include "util/units.h"
|
||||
|
||||
// DMA Controllers
|
||||
|
||||
static DMAControllerState s_dma1_state;
|
||||
static DMAController DMA1_DEVICE = {
|
||||
.state = &s_dma1_state,
|
||||
.periph = DMA1,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA1,
|
||||
};
|
||||
|
||||
static DMAControllerState s_dma2_state;
|
||||
static DMAController DMA2_DEVICE = {
|
||||
.state = &s_dma2_state,
|
||||
.periph = DMA2,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA2,
|
||||
};
|
||||
|
||||
// DMA Streams
|
||||
|
||||
CREATE_DMA_STREAM(1, 1); // DMA1_STREAM1_DEVICE - Debug UART RX
|
||||
CREATE_DMA_STREAM(1, 3); // DMA1_STREAM3_DEVICE - Mic I2S RX
|
||||
CREATE_DMA_STREAM(1, 6); // DMA1_STREAM6_DEVICE - Accessory UART RX
|
||||
CREATE_DMA_STREAM(2, 0); // DMA2_STREAM0_DEVICE - Compositor DMA
|
||||
CREATE_DMA_STREAM(2, 5); // DMA2_STREAM5_DEVICE - ICE40LP TX
|
||||
|
||||
// DMA Requests
|
||||
|
||||
static DMARequestState s_dbg_uart_dma_request_state;
|
||||
static DMARequest DBG_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_dbg_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM1_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_mic_i2s_rx_dma_request_state;
|
||||
static DMARequest MIC_I2S_RX_DMA_REQUEST = {
|
||||
.state = &s_mic_i2s_rx_dma_request_state,
|
||||
.stream = &DMA1_STREAM3_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_HalfWord,
|
||||
};
|
||||
DMARequest * const MIC_I2S_RX_DMA = &MIC_I2S_RX_DMA_REQUEST;
|
||||
|
||||
static DMARequestState s_accessory_uart_dma_request_state;
|
||||
static DMARequest ACCESSORY_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_accessory_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM6_DEVICE,
|
||||
.channel = 5,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_compositor_dma_request_state;
|
||||
static DMARequest COMPOSITOR_DMA_REQUEST = {
|
||||
.state = &s_compositor_dma_request_state,
|
||||
.stream = &DMA2_STREAM0_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 11,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_MemoryToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
DMARequest * const COMPOSITOR_DMA = &COMPOSITOR_DMA_REQUEST;
|
||||
|
||||
static DMARequestState s_ice40lp_spi_tx_dma_request_state;
|
||||
static DMARequest ICE40LP_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_ice40lp_spi_tx_dma_request_state,
|
||||
.stream = &DMA2_STREAM5_DEVICE,
|
||||
.channel = 1,
|
||||
// Use the same priority as the EXTI handlers so that the DMA-complete
|
||||
// handler doesn't preempt the display BUSY (INTn) handler.
|
||||
.irq_priority = 0x0e,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
|
||||
// UART DEVICES
|
||||
|
||||
#if TARGET_QEMU
|
||||
static UARTDeviceState s_qemu_uart_state;
|
||||
static UARTDevice QEMU_UART_DEVICE = {
|
||||
.state = &s_qemu_uart_state,
|
||||
// GPIO? Where we're going, we don't need GPIO. (connected to QEMU)
|
||||
.periph = USART2,
|
||||
.irq_channel = USART2_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2
|
||||
};
|
||||
UARTDevice * const QEMU_UART = &QEMU_UART_DEVICE;
|
||||
IRQ_MAP(USART2, uart_irq_handler, QEMU_UART);
|
||||
#endif
|
||||
|
||||
static UARTDeviceState s_dbg_uart_state;
|
||||
static UARTDevice DBG_UART_DEVICE = {
|
||||
.state = &s_dbg_uart_state,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.rx_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.periph = USART3,
|
||||
.irq_channel = USART3_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART3,
|
||||
.rx_dma = &DBG_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const DBG_UART = &DBG_UART_DEVICE;
|
||||
IRQ_MAP(USART3, uart_irq_handler, DBG_UART);
|
||||
|
||||
static UARTDeviceState s_accessory_uart_state;
|
||||
static UARTDevice ACCESSORY_UART_DEVICE = {
|
||||
.state = &s_accessory_uart_state,
|
||||
.half_duplex = true,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOE,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
.gpio_pin_source = GPIO_PinSource1,
|
||||
.gpio_af = GPIO_AF_UART8
|
||||
},
|
||||
.periph = UART8,
|
||||
.irq_channel = UART8_IRQn,
|
||||
.irq_priority = 0xb,
|
||||
.rcc_apb_periph = RCC_APB1Periph_UART8,
|
||||
.rx_dma = &ACCESSORY_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const ACCESSORY_UART = &ACCESSORY_UART_DEVICE;
|
||||
IRQ_MAP(UART8, uart_irq_handler, ACCESSORY_UART);
|
||||
|
||||
|
||||
// I2C DEVICES
|
||||
|
||||
static I2CBusState I2C_PMIC_MAG_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_PMIC_MAG_BUS_HAL = {
|
||||
.i2c = I2C1,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C1,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_16_9,
|
||||
.ev_irq_channel = I2C1_EV_IRQn,
|
||||
.er_irq_channel = I2C1_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_PMIC_MAG_BUS = {
|
||||
.state = &I2C_PMIC_MAG_BUS_STATE,
|
||||
.hal = &I2C_PMIC_MAG_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_6,
|
||||
.gpio_pin_source = GPIO_PinSource6,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
.gpio_pin_source = GPIO_PinSource9,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C1,
|
||||
.name = "I2C_PMIC_MAG"
|
||||
};
|
||||
|
||||
extern void i2c_rail_ctl_pmic(I2CBus *device, bool enable);
|
||||
|
||||
static I2CBusState I2C_MFI_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_MFI_BUS_HAL = {
|
||||
.i2c = I2C2,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C2,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_16_9,
|
||||
.ev_irq_channel = I2C2_EV_IRQn,
|
||||
.er_irq_channel = I2C2_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_MFI_BUS = {
|
||||
.state = &I2C_MFI_BUS_STATE,
|
||||
.hal = &I2C_MFI_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
.gpio_pin_source = GPIO_PinSource1,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
.gpio_pin_source = GPIO_PinSource0,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C2,
|
||||
.rail_ctl_fn = i2c_rail_ctl_pmic,
|
||||
.name = "I2C_MFI"
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAX14690 = {
|
||||
.bus = &I2C_PMIC_MAG_BUS,
|
||||
.address = 0x50
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MFI = {
|
||||
.bus = &I2C_MFI_BUS,
|
||||
.address = 0x20
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAG3110 = {
|
||||
.bus = &I2C_PMIC_MAG_BUS,
|
||||
.address = 0x1C
|
||||
};
|
||||
|
||||
I2CSlavePort * const I2C_MAX14690 = &I2C_SLAVE_MAX14690;
|
||||
I2CSlavePort * const I2C_MFI = &I2C_SLAVE_MFI;
|
||||
I2CSlavePort * const I2C_MAG3110 = &I2C_SLAVE_MAG3110;
|
||||
|
||||
IRQ_MAP(I2C1_EV, i2c_hal_event_irq_handler, &I2C_PMIC_MAG_BUS);
|
||||
IRQ_MAP(I2C1_ER, i2c_hal_error_irq_handler, &I2C_PMIC_MAG_BUS);
|
||||
IRQ_MAP(I2C2_EV, i2c_hal_event_irq_handler, &I2C_MFI_BUS);
|
||||
IRQ_MAP(I2C2_ER, i2c_hal_error_irq_handler, &I2C_MFI_BUS);
|
||||
|
||||
|
||||
// VOLTAGE MONITOR DEVICES
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_ALS_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_2,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_BATTERY_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_1,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
}
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_TEMPERATURE_DEVICE = {
|
||||
.adc = ADC1,
|
||||
.adc_channel = ADC_Channel_TempSensor,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC1,
|
||||
// .input not applicable
|
||||
};
|
||||
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS = &VOLTAGE_MONITOR_ALS_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY = &VOLTAGE_MONITOR_BATTERY_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_TEMPERATURE = &VOLTAGE_MONITOR_TEMPERATURE_DEVICE;
|
||||
|
||||
// Temperature sensor
|
||||
// STM32F439 datasheet rev 5
|
||||
// Section 6.3.22
|
||||
const TemperatureSensor TEMPERATURE_SENSOR_DEVICE = {
|
||||
.voltage_monitor = &VOLTAGE_MONITOR_TEMPERATURE_DEVICE,
|
||||
.millivolts_ref = 760,
|
||||
.millidegrees_ref = 25000,
|
||||
.slope_numerator = 5,
|
||||
.slope_denominator = 2000,
|
||||
};
|
||||
|
||||
const TemperatureSensor * const TEMPERATURE_SENSOR = &TEMPERATURE_SENSOR_DEVICE;
|
||||
|
||||
//
|
||||
// SPI Bus configuration
|
||||
//
|
||||
|
||||
static SPIBusState BMI160_SPI_BUS_STATE = {};
|
||||
static const SPIBus BMI160_SPI_BUS = {
|
||||
.state = &BMI160_SPI_BUS_STATE,
|
||||
.spi = SPI1,
|
||||
.spi_sclk = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_5,
|
||||
.gpio_pin_source = GPIO_PinSource5,
|
||||
.gpio_af = GPIO_AF_SPI1
|
||||
},
|
||||
.spi_miso = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_6,
|
||||
.gpio_pin_source = GPIO_PinSource6,
|
||||
.gpio_af = GPIO_AF_SPI1
|
||||
},
|
||||
.spi_mosi = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF_SPI1
|
||||
},
|
||||
.spi_sclk_speed = GPIO_Speed_50MHz,
|
||||
.spi_clock_speed_hz = MHZ_TO_HZ(5),
|
||||
};
|
||||
|
||||
static SPIBusState ICE40LP_SPI_BUS_STATE = {};
|
||||
static const SPIBus ICE40LP_SPI_BUS = {
|
||||
.state = &ICE40LP_SPI_BUS_STATE,
|
||||
.spi = SPI6,
|
||||
.spi_sclk = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_13,
|
||||
.gpio_pin_source = GPIO_PinSource13,
|
||||
.gpio_af = GPIO_AF_SPI6
|
||||
},
|
||||
.spi_miso = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_12,
|
||||
.gpio_pin_source = GPIO_PinSource12,
|
||||
.gpio_af = GPIO_AF_SPI6
|
||||
},
|
||||
.spi_mosi = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_14,
|
||||
.gpio_pin_source = GPIO_PinSource14,
|
||||
.gpio_af = GPIO_AF_SPI6
|
||||
},
|
||||
.spi_sclk_speed = GPIO_Speed_25MHz,
|
||||
.spi_clock_speed_hz = MHZ_TO_HZ(16),
|
||||
};
|
||||
|
||||
//
|
||||
// SPI Slave port configuration
|
||||
//
|
||||
static SPISlavePortState BMI160_SPI_SLAVE_PORT_STATE = {};
|
||||
static SPISlavePort BMI160_SPI_SLAVE_PORT = {
|
||||
.slave_state = &BMI160_SPI_SLAVE_PORT_STATE,
|
||||
.spi_bus = &BMI160_SPI_BUS,
|
||||
.spi_scs = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_4,
|
||||
.active_high = false
|
||||
},
|
||||
.spi_direction = SpiDirection_2LinesFullDuplex,
|
||||
.spi_cpol = SpiCPol_Low,
|
||||
.spi_cpha = SpiCPha_1Edge,
|
||||
.spi_first_bit = SpiFirstBit_MSB,
|
||||
};
|
||||
SPISlavePort * const BMI160_SPI = &BMI160_SPI_SLAVE_PORT;
|
||||
|
||||
static SPISlavePortState ICE40LP_SPI_SLAVE_PORT_STATE = {};
|
||||
static SPISlavePort ICE40LP_SPI_SLAVE_PORT = {
|
||||
.slave_state = &ICE40LP_SPI_SLAVE_PORT_STATE,
|
||||
.spi_bus = &ICE40LP_SPI_BUS,
|
||||
.spi_scs = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.active_high = false
|
||||
},
|
||||
.spi_direction = SpiDirection_1LineTx,
|
||||
.spi_cpol = SpiCPol_High,
|
||||
.spi_cpha = SpiCPha_2Edge,
|
||||
.spi_first_bit = SpiFirstBit_MSB,
|
||||
.tx_dma = &ICE40LP_SPI_TX_DMA_REQUEST
|
||||
};
|
||||
|
||||
//
|
||||
// iCE40LP configuration
|
||||
//
|
||||
static ICE40LPDeviceState s_ice40lp_state;
|
||||
static ICE40LPDevice ICE40LP_DEVICE = {
|
||||
.state = &s_ice40lp_state,
|
||||
|
||||
.spi_port = &ICE40LP_SPI_SLAVE_PORT,
|
||||
.base_spi_frequency = MHZ_TO_HZ(16),
|
||||
.fast_spi_frequency = MHZ_TO_HZ(32),
|
||||
.creset = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_15,
|
||||
.active_high = true,
|
||||
},
|
||||
.cdone = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
},
|
||||
.busy = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
},
|
||||
.cdone_exti = {
|
||||
.exti_port_source = EXTI_PortSourceGPIOG,
|
||||
.exti_line = 9,
|
||||
},
|
||||
.busy_exti = {
|
||||
.exti_port_source = EXTI_PortSourceGPIOG,
|
||||
.exti_line = 10,
|
||||
},
|
||||
.use_6v6_rail = true,
|
||||
};
|
||||
ICE40LPDevice * const ICE40LP = &ICE40LP_DEVICE;
|
||||
|
||||
|
||||
void board_early_init(void) {
|
||||
spi_slave_port_init(ICE40LP->spi_port);
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
i2c_init(&I2C_PMIC_MAG_BUS);
|
||||
i2c_init(&I2C_MFI_BUS);
|
||||
spi_slave_port_init(BMI160_SPI);
|
||||
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_ALS);
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_BATTERY);
|
||||
}
|
272
src/fw/board/boards/board_snowy.h
Normal file
272
src/fw/board/boards/board_snowy.h
Normal file
|
@ -0,0 +1,272 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
// ----------------------------------------------
|
||||
// Board definitions for Snowy EVT2 and similar
|
||||
// ----------------------------------------------
|
||||
//
|
||||
// This includes snowy_evt2, snowy_dvt and snowy_bb2. Except for a couple of
|
||||
// minor quirks, all of the boards using this file are electrically identical.
|
||||
|
||||
#include "drivers/imu/bmi160/bmi160.h"
|
||||
#include "services/imu/units.h"
|
||||
#include "util/size.h"
|
||||
|
||||
#define BOARD_LSE_MODE RCC_LSE_Bypass
|
||||
|
||||
static const BoardConfig BOARD_CONFIG = {
|
||||
.has_mic = true,
|
||||
.mic_config = {
|
||||
.i2s_ck = { GPIOB, GPIO_Pin_10, GPIO_PinSource10, GPIO_AF_SPI2 },
|
||||
.i2s_sd = { GPIOB, GPIO_Pin_15, GPIO_PinSource15, GPIO_AF_SPI2 },
|
||||
.spi = SPI2,
|
||||
.spi_clock_ctrl = RCC_APB1Periph_SPI2,
|
||||
#ifdef IS_BIGBOARD
|
||||
.gain = 100,
|
||||
#else
|
||||
.gain = 250,
|
||||
#endif
|
||||
},
|
||||
|
||||
#ifdef BOARD_SNOWY_S3
|
||||
.ambient_light_dark_threshold = 3220,
|
||||
#else
|
||||
.ambient_light_dark_threshold = 3130,
|
||||
#endif
|
||||
.ambient_k_delta_threshold = 96,
|
||||
.photo_en = { GPIOA, GPIO_Pin_3, true },
|
||||
|
||||
.dbgserial_int = { EXTI_PortSourceGPIOC, 12 },
|
||||
.dbgserial_int_gpio = { GPIOC, GPIO_Pin_12 },
|
||||
|
||||
// Only used with Sharp displays
|
||||
.lcd_com = { 0 },
|
||||
|
||||
.power_5v0_options = OptionNotPresent,
|
||||
.power_ctl_5v0 = { 0 },
|
||||
|
||||
.backlight_on_percent = 45,
|
||||
.backlight_max_duty_cycle_percent = 100,
|
||||
|
||||
.fpc_pinstrap_1 = { GPIOB, GPIO_Pin_0 },
|
||||
.fpc_pinstrap_2 = { GPIOC, GPIO_Pin_5 },
|
||||
|
||||
#ifdef IS_BIGBOARD
|
||||
.num_avail_gpios = 140,
|
||||
#else
|
||||
.num_avail_gpios = 114,
|
||||
#endif
|
||||
};
|
||||
|
||||
static const BoardConfigButton BOARD_CONFIG_BUTTON = {
|
||||
.buttons = {
|
||||
[BUTTON_ID_BACK] = { "Back", GPIOG, GPIO_Pin_4, { EXTI_PortSourceGPIOG, 4 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_UP] = { "Up", GPIOG, GPIO_Pin_3, { EXTI_PortSourceGPIOG, 3 }, GPIO_PuPd_UP },
|
||||
[BUTTON_ID_SELECT] = { "Select", GPIOG, GPIO_Pin_1, { EXTI_PortSourceGPIOG, 1 }, GPIO_PuPd_UP },
|
||||
[BUTTON_ID_DOWN] = { "Down", GPIOG, GPIO_Pin_2, { EXTI_PortSourceGPIOG, 2 }, GPIO_PuPd_UP },
|
||||
},
|
||||
|
||||
.button_com = { 0 },
|
||||
.active_high = false,
|
||||
};
|
||||
|
||||
static const BoardConfigPower BOARD_CONFIG_POWER = {
|
||||
.pmic_int = { EXTI_PortSourceGPIOG, 7 },
|
||||
.pmic_int_gpio = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
},
|
||||
|
||||
.rail_4V5_ctrl = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
.active_high = true,
|
||||
},
|
||||
.rail_6V6_ctrl = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_3,
|
||||
.active_high = true,
|
||||
},
|
||||
.rail_6V6_ctrl_otype = GPIO_OType_OD,
|
||||
|
||||
.battery_vmon_scale = {
|
||||
// The PMIC divides the battery voltage by a ratio of 3:1 in order to move it down to a voltage
|
||||
// our ADC is capable of reading. The battery voltage varies around 4V~ and we're only capable
|
||||
// of reading up to 1.8V in the ADC.
|
||||
.numerator = 3,
|
||||
.denominator = 1,
|
||||
},
|
||||
|
||||
.vusb_stat = { .gpio = GPIO_Port_NULL, },
|
||||
.chg_stat = { GPIO_Port_NULL },
|
||||
.chg_fast = { GPIO_Port_NULL },
|
||||
.chg_en = { GPIO_Port_NULL },
|
||||
.has_vusb_interrupt = false,
|
||||
|
||||
.wake_on_usb_power = false,
|
||||
|
||||
#if defined(IS_BIGBOARD) && !defined(BATTERY_DEBUG)
|
||||
.charging_cutoff_voltage = 4200,
|
||||
#else
|
||||
.charging_cutoff_voltage = 4300,
|
||||
#endif
|
||||
.charging_status_led_voltage_compensation = 0,
|
||||
|
||||
#ifdef BOARD_SNOWY_S3
|
||||
.low_power_threshold = 2,
|
||||
.battery_capacity_hours = 204,
|
||||
#else
|
||||
.low_power_threshold = 3,
|
||||
.battery_capacity_hours = 144,
|
||||
#endif
|
||||
};
|
||||
|
||||
static const BoardConfigAccel BOARD_CONFIG_ACCEL = {
|
||||
.accel_config = {
|
||||
#ifdef IS_BIGBOARD
|
||||
.axes_offsets[AXIS_X] = 0,
|
||||
.axes_offsets[AXIS_Y] = 1,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = false,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
#else
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = false,
|
||||
.axes_inverts[AXIS_Z] = false,
|
||||
#endif
|
||||
.shake_thresholds[AccelThresholdHigh] = 0x64,
|
||||
.shake_thresholds[AccelThresholdLow] = 0xf,
|
||||
.double_tap_threshold = 12500,
|
||||
},
|
||||
.accel_int_gpios = {
|
||||
[0] = { GPIOG, GPIO_Pin_5 },
|
||||
[1] = { GPIOG, GPIO_Pin_6 },
|
||||
},
|
||||
.accel_ints = {
|
||||
[0] = { EXTI_PortSourceGPIOG, 5 },
|
||||
[1] = { EXTI_PortSourceGPIOG, 6 }
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMag BOARD_CONFIG_MAG = {
|
||||
.mag_config = {
|
||||
#ifdef IS_BIGBOARD
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
#else
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = true,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = false,
|
||||
#endif
|
||||
},
|
||||
.mag_int_gpio = { GPIOF, GPIO_Pin_14 },
|
||||
.mag_int = { EXTI_PortSourceGPIOF, 14 },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_VIBE = {
|
||||
.options = ActuatorOptions_Ctl | ActuatorOptions_Pwm | ActuatorOptions_HBridge,
|
||||
.ctl = { GPIOF, GPIO_Pin_4, true },
|
||||
.pwm = {
|
||||
.output = { GPIOB, GPIO_Pin_8, true },
|
||||
.timer = {
|
||||
.peripheral = TIM10,
|
||||
.config_clock = RCC_APB2Periph_TIM10,
|
||||
.init = TIM_OC1Init,
|
||||
.preload = TIM_OC1PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOB, GPIO_Pin_8, GPIO_PinSource8, GPIO_AF_TIM10 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_BACKLIGHT = {
|
||||
.options = ActuatorOptions_Pwm,
|
||||
.ctl = {0},
|
||||
.pwm = {
|
||||
.output = { GPIOB, GPIO_Pin_14, true },
|
||||
.timer = {
|
||||
.peripheral = TIM12,
|
||||
.config_clock = RCC_APB1Periph_TIM12,
|
||||
.init = TIM_OC1Init,
|
||||
.preload = TIM_OC1PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOB, GPIO_Pin_14, GPIO_PinSource14, GPIO_AF_TIM12 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigAccessory BOARD_CONFIG_ACCESSORY = {
|
||||
.power_en = { GPIOF, GPIO_Pin_13, true },
|
||||
.int_gpio = { GPIOE, GPIO_Pin_0 },
|
||||
.exti = { EXTI_PortSourceGPIOE, 0 },
|
||||
};
|
||||
|
||||
#define BOARD_BT_USART_IRQ_HANDLER USART1_IRQHandler
|
||||
static const BoardConfigBTCommon BOARD_CONFIG_BT_COMMON = {
|
||||
.controller = CC2564B,
|
||||
.shutdown = { GPIOB, GPIO_Pin_12, false },
|
||||
.wakeup = {
|
||||
.int_gpio = { GPIOA, GPIO_Pin_11 },
|
||||
.int_exti = { EXTI_PortSourceGPIOA, 11 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMCO1 BOARD_CONFIG_MCO1 = {
|
||||
.output_enabled = true,
|
||||
.af_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_MCO,
|
||||
},
|
||||
.an_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
},
|
||||
};
|
||||
|
||||
extern DMARequest * const COMPOSITOR_DMA;
|
||||
extern DMARequest * const MIC_I2S_RX_DMA;
|
||||
|
||||
extern UARTDevice * const QEMU_UART;
|
||||
extern UARTDevice * const DBG_UART;
|
||||
extern UARTDevice * const ACCESSORY_UART;
|
||||
|
||||
extern SPISlavePort * const BMI160_SPI;
|
||||
|
||||
extern I2CSlavePort * const I2C_MAG3110;
|
||||
extern I2CSlavePort * const I2C_MAX14690;
|
||||
extern I2CSlavePort * const I2C_MFI;
|
||||
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS;
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY;
|
||||
|
||||
extern const TemperatureSensor * const TEMPERATURE_SENSOR;
|
||||
|
||||
static MicDevice * const MIC = (void *)0;
|
||||
|
||||
extern ICE40LPDevice * const ICE40LP;
|
410
src/fw/board/boards/board_spalding_evt.c
Normal file
410
src/fw/board/boards/board_spalding_evt.c
Normal file
|
@ -0,0 +1,410 @@
|
|||
/*
|
||||
* 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/display/ice40lp/ice40lp_definitions.h"
|
||||
#include "drivers/i2c_definitions.h"
|
||||
#include "drivers/stm32f2/dma_definitions.h"
|
||||
#include "drivers/stm32f2/i2c_hal_definitions.h"
|
||||
#include "drivers/stm32f2/spi_definitions.h"
|
||||
#include "drivers/stm32f2/uart_definitions.h"
|
||||
#include "drivers/temperature.h"
|
||||
#include "drivers/voltage_monitor.h"
|
||||
#include "util/units.h"
|
||||
|
||||
// DMA Controllers
|
||||
|
||||
static DMAControllerState s_dma1_state;
|
||||
static DMAController DMA1_DEVICE = {
|
||||
.state = &s_dma1_state,
|
||||
.periph = DMA1,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA1,
|
||||
};
|
||||
|
||||
static DMAControllerState s_dma2_state;
|
||||
static DMAController DMA2_DEVICE = {
|
||||
.state = &s_dma2_state,
|
||||
.periph = DMA2,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA2,
|
||||
};
|
||||
|
||||
// DMA Streams
|
||||
|
||||
CREATE_DMA_STREAM(1, 1); // DMA1_STREAM1_DEVICE - Debug UART RX
|
||||
CREATE_DMA_STREAM(1, 3); // DMA1_STREAM3_DEVICE - Mic I2S RX
|
||||
CREATE_DMA_STREAM(1, 6); // DMA1_STREAM6_DEVICE - Accessory UART RX
|
||||
CREATE_DMA_STREAM(2, 0); // DMA2_STREAM0_DEVICE - Compositor DMA
|
||||
CREATE_DMA_STREAM(2, 5); // DMA2_STREAM5_DEVICE - ICE40LP TX
|
||||
|
||||
// DMA Requests
|
||||
|
||||
static DMARequestState s_dbg_uart_dma_request_state;
|
||||
static DMARequest DBG_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_dbg_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM1_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_mic_i2s_rx_dma_request_state;
|
||||
static DMARequest MIC_I2S_RX_DMA_REQUEST = {
|
||||
.state = &s_mic_i2s_rx_dma_request_state,
|
||||
.stream = &DMA1_STREAM3_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_HalfWord,
|
||||
};
|
||||
DMARequest * const MIC_I2S_RX_DMA = &MIC_I2S_RX_DMA_REQUEST;
|
||||
|
||||
static DMARequestState s_accessory_uart_dma_request_state;
|
||||
static DMARequest ACCESSORY_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_accessory_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM6_DEVICE,
|
||||
.channel = 5,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_compositor_dma_request_state;
|
||||
static DMARequest COMPOSITOR_DMA_REQUEST = {
|
||||
.state = &s_compositor_dma_request_state,
|
||||
.stream = &DMA2_STREAM0_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 11,
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_MemoryToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
DMARequest * const COMPOSITOR_DMA = &COMPOSITOR_DMA_REQUEST;
|
||||
|
||||
static DMARequestState s_ice40lp_spi_tx_dma_request_state;
|
||||
static DMARequest ICE40LP_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_ice40lp_spi_tx_dma_request_state,
|
||||
.stream = &DMA2_STREAM5_DEVICE,
|
||||
.channel = 1,
|
||||
// Use the same priority as the EXTI handlers so that the DMA-complete
|
||||
// handler doesn't preempt the display BUSY (INTn) handler.
|
||||
.irq_priority = 0x0e,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
|
||||
// UART DEVICES
|
||||
|
||||
#if TARGET_QEMU
|
||||
static UARTDeviceState s_qemu_uart_state;
|
||||
static UARTDevice QEMU_UART_DEVICE = {
|
||||
.state = &s_qemu_uart_state,
|
||||
// GPIO? Where we're going, we don't need GPIO. (connected to QEMU)
|
||||
.periph = USART2,
|
||||
.irq_channel = USART2_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2
|
||||
};
|
||||
UARTDevice * const QEMU_UART = &QEMU_UART_DEVICE;
|
||||
IRQ_MAP(USART2, uart_irq_handler, QEMU_UART);
|
||||
#endif
|
||||
|
||||
static UARTDeviceState s_dbg_uart_state;
|
||||
static UARTDevice DBG_UART_DEVICE = {
|
||||
.state = &s_dbg_uart_state,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.rx_gpio = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.periph = USART3,
|
||||
.irq_channel = USART3_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART3,
|
||||
.rx_dma = &DBG_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const DBG_UART = &DBG_UART_DEVICE;
|
||||
IRQ_MAP(USART3, uart_irq_handler, DBG_UART);
|
||||
|
||||
static UARTDeviceState s_accessory_uart_state;
|
||||
static UARTDevice ACCESSORY_UART_DEVICE = {
|
||||
.state = &s_accessory_uart_state,
|
||||
.half_duplex = true,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOE,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
.gpio_pin_source = GPIO_PinSource1,
|
||||
.gpio_af = GPIO_AF_UART8
|
||||
},
|
||||
.periph = UART8,
|
||||
.irq_channel = UART8_IRQn,
|
||||
.irq_priority = 0xb,
|
||||
.rcc_apb_periph = RCC_APB1Periph_UART8,
|
||||
.rx_dma = &ACCESSORY_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const ACCESSORY_UART = &ACCESSORY_UART_DEVICE;
|
||||
IRQ_MAP(UART8, uart_irq_handler, ACCESSORY_UART);
|
||||
|
||||
|
||||
// I2C DEVICES
|
||||
|
||||
static I2CBusState I2C_PMIC_MAG_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_PMIC_MAG_BUS_HAL = {
|
||||
.i2c = I2C1,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C1,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_16_9,
|
||||
.ev_irq_channel = I2C1_EV_IRQn,
|
||||
.er_irq_channel = I2C1_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_PMIC_MAG_BUS = {
|
||||
.state = &I2C_PMIC_MAG_BUS_STATE,
|
||||
.hal = &I2C_PMIC_MAG_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_6,
|
||||
.gpio_pin_source = GPIO_PinSource6,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
.gpio_pin_source = GPIO_PinSource9,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C1,
|
||||
.name = "I2C_PMIC_MAG"
|
||||
};
|
||||
|
||||
extern void i2c_rail_ctl_pmic(I2CBus *device, bool enable);
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAX14690 = {
|
||||
.bus = &I2C_PMIC_MAG_BUS,
|
||||
.address = 0x50
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAG3110 = {
|
||||
.bus = &I2C_PMIC_MAG_BUS,
|
||||
.address = 0x1C
|
||||
};
|
||||
|
||||
I2CSlavePort * const I2C_MAX14690 = &I2C_SLAVE_MAX14690;
|
||||
I2CSlavePort * const I2C_MAG3110 = &I2C_SLAVE_MAG3110;
|
||||
I2CSlavePort * const I2C_MFI = NULL;
|
||||
|
||||
IRQ_MAP(I2C1_EV, i2c_hal_event_irq_handler, &I2C_PMIC_MAG_BUS);
|
||||
IRQ_MAP(I2C1_ER, i2c_hal_error_irq_handler, &I2C_PMIC_MAG_BUS);
|
||||
|
||||
|
||||
// VOLTAGE MONITOR DEVICES
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_ALS_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_2,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_BATTERY_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_1,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_1,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_TEMPERATURE_DEVICE = {
|
||||
.adc = ADC1,
|
||||
.adc_channel = ADC_Channel_TempSensor,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC1,
|
||||
// .input not applicable
|
||||
};
|
||||
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS = &VOLTAGE_MONITOR_ALS_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY = &VOLTAGE_MONITOR_BATTERY_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_TEMPERATURE = &VOLTAGE_MONITOR_TEMPERATURE_DEVICE;
|
||||
|
||||
// Temperature sensor
|
||||
// STM32F439 datasheet rev 5
|
||||
// Section 6.3.22
|
||||
const TemperatureSensor TEMPERATURE_SENSOR_DEVICE = {
|
||||
.voltage_monitor = &VOLTAGE_MONITOR_TEMPERATURE_DEVICE,
|
||||
.millivolts_ref = 760,
|
||||
.millidegrees_ref = 25000,
|
||||
.slope_numerator = 5,
|
||||
.slope_denominator = 2000,
|
||||
};
|
||||
|
||||
const TemperatureSensor * const TEMPERATURE_SENSOR = &TEMPERATURE_SENSOR_DEVICE;
|
||||
|
||||
//
|
||||
// SPI Bus configuration
|
||||
//
|
||||
|
||||
static SPIBusState BMI160_SPI_BUS_STATE = {};
|
||||
static const SPIBus BMI160_SPI_BUS = {
|
||||
.state = &BMI160_SPI_BUS_STATE,
|
||||
.spi = SPI1,
|
||||
.spi_sclk = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_5,
|
||||
.gpio_pin_source = GPIO_PinSource5,
|
||||
.gpio_af = GPIO_AF_SPI1
|
||||
},
|
||||
.spi_miso = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_6,
|
||||
.gpio_pin_source = GPIO_PinSource6,
|
||||
.gpio_af = GPIO_AF_SPI1
|
||||
},
|
||||
.spi_mosi = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF_SPI1
|
||||
},
|
||||
.spi_sclk_speed = GPIO_Speed_50MHz,
|
||||
.spi_clock_speed_hz = MHZ_TO_HZ(5),
|
||||
};
|
||||
|
||||
static SPIBusState ICE40LP_SPI_BUS_STATE = {};
|
||||
static const SPIBus ICE40LP_SPI_BUS = {
|
||||
.state = &ICE40LP_SPI_BUS_STATE,
|
||||
.spi = SPI6,
|
||||
.spi_sclk = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_13,
|
||||
.gpio_pin_source = GPIO_PinSource13,
|
||||
.gpio_af = GPIO_AF_SPI6
|
||||
},
|
||||
.spi_miso = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_12,
|
||||
.gpio_pin_source = GPIO_PinSource12,
|
||||
.gpio_af = GPIO_AF_SPI6
|
||||
},
|
||||
.spi_mosi = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_14,
|
||||
.gpio_pin_source = GPIO_PinSource14,
|
||||
.gpio_af = GPIO_AF_SPI6
|
||||
},
|
||||
.spi_sclk_speed = GPIO_Speed_25MHz,
|
||||
.spi_clock_speed_hz = MHZ_TO_HZ(16),
|
||||
};
|
||||
|
||||
//
|
||||
// SPI Slave port configuration
|
||||
//
|
||||
static SPISlavePortState BMI160_SPI_SLAVE_PORT_STATE = {};
|
||||
static SPISlavePort BMI160_SPI_SLAVE_PORT = {
|
||||
.slave_state = &BMI160_SPI_SLAVE_PORT_STATE,
|
||||
.spi_bus = &BMI160_SPI_BUS,
|
||||
.spi_scs = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_4,
|
||||
.active_high = false
|
||||
},
|
||||
.spi_direction = SpiDirection_2LinesFullDuplex,
|
||||
.spi_cpol = SpiCPol_Low,
|
||||
.spi_cpha = SpiCPha_1Edge,
|
||||
.spi_first_bit = SpiFirstBit_MSB,
|
||||
};
|
||||
SPISlavePort * const BMI160_SPI = &BMI160_SPI_SLAVE_PORT;
|
||||
|
||||
static SPISlavePortState ICE40LP_SPI_SLAVE_PORT_STATE = {};
|
||||
static SPISlavePort ICE40LP_SPI_SLAVE_PORT = {
|
||||
.slave_state = &ICE40LP_SPI_SLAVE_PORT_STATE,
|
||||
.spi_bus = &ICE40LP_SPI_BUS,
|
||||
.spi_scs = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.active_high = false
|
||||
},
|
||||
.spi_direction = SpiDirection_1LineTx,
|
||||
.spi_cpol = SpiCPol_High,
|
||||
.spi_cpha = SpiCPha_2Edge,
|
||||
.spi_first_bit = SpiFirstBit_MSB,
|
||||
.tx_dma = &ICE40LP_SPI_TX_DMA_REQUEST
|
||||
};
|
||||
|
||||
//
|
||||
// iCE40LP configuration
|
||||
//
|
||||
static ICE40LPDeviceState s_ice40lp_state;
|
||||
static ICE40LPDevice ICE40LP_DEVICE = {
|
||||
.state = &s_ice40lp_state,
|
||||
|
||||
.spi_port = &ICE40LP_SPI_SLAVE_PORT,
|
||||
.base_spi_frequency = MHZ_TO_HZ(16),
|
||||
.fast_spi_frequency = MHZ_TO_HZ(32),
|
||||
.creset = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_15,
|
||||
.active_high = true,
|
||||
},
|
||||
.cdone = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
},
|
||||
.busy = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
},
|
||||
.cdone_exti = {
|
||||
.exti_port_source = EXTI_PortSourceGPIOG,
|
||||
.exti_line = 9,
|
||||
},
|
||||
.busy_exti = {
|
||||
.exti_port_source = EXTI_PortSourceGPIOG,
|
||||
.exti_line = 10,
|
||||
},
|
||||
.use_6v6_rail = true,
|
||||
};
|
||||
ICE40LPDevice * const ICE40LP = &ICE40LP_DEVICE;
|
||||
|
||||
|
||||
void board_early_init(void) {
|
||||
spi_slave_port_init(ICE40LP->spi_port);
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
i2c_init(&I2C_PMIC_MAG_BUS);
|
||||
spi_slave_port_init(BMI160_SPI);
|
||||
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_ALS);
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_BATTERY);
|
||||
}
|
239
src/fw/board/boards/board_spalding_evt.h
Normal file
239
src/fw/board/boards/board_spalding_evt.h
Normal file
|
@ -0,0 +1,239 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
// ------------------------------------
|
||||
// Board definitions for Spalding EVT
|
||||
// ------------------------------------
|
||||
|
||||
#include "drivers/imu/bmi160/bmi160.h"
|
||||
#include "services/imu/units.h"
|
||||
#include "util/size.h"
|
||||
|
||||
#define BOARD_LSE_MODE RCC_LSE_Bypass
|
||||
|
||||
static const BoardConfig BOARD_CONFIG = {
|
||||
.has_mic = true,
|
||||
.mic_config = {
|
||||
.i2s_ck = { GPIOB, GPIO_Pin_10, GPIO_PinSource10, GPIO_AF_SPI2 },
|
||||
.i2s_sd = { GPIOB, GPIO_Pin_15, GPIO_PinSource15, GPIO_AF_SPI2 },
|
||||
.spi = SPI2,
|
||||
.spi_clock_ctrl = RCC_APB1Periph_SPI2,
|
||||
.gain = 250,
|
||||
},
|
||||
|
||||
.ambient_light_dark_threshold = 3130,
|
||||
.ambient_k_delta_threshold = 96,
|
||||
.photo_en = { GPIOA, GPIO_Pin_3, true },
|
||||
|
||||
.dbgserial_int = { EXTI_PortSourceGPIOC, 12 },
|
||||
.dbgserial_int_gpio = { GPIOC, GPIO_Pin_12 },
|
||||
|
||||
// Only used with Sharp displays
|
||||
.lcd_com = { 0 },
|
||||
|
||||
.power_5v0_options = OptionNotPresent,
|
||||
.power_ctl_5v0 = { 0 },
|
||||
|
||||
.backlight_on_percent = 25,
|
||||
.backlight_max_duty_cycle_percent = 100,
|
||||
|
||||
.fpc_pinstrap_1 = { GPIOB, GPIO_Pin_0 },
|
||||
.fpc_pinstrap_2 = { GPIOC, GPIO_Pin_5 },
|
||||
|
||||
.num_avail_gpios = 114,
|
||||
};
|
||||
|
||||
static const BoardConfigButton BOARD_CONFIG_BUTTON = {
|
||||
.buttons = {
|
||||
[BUTTON_ID_BACK] = {
|
||||
"Back", GPIOG, GPIO_Pin_4, { EXTI_PortSourceGPIOG, 4 }, GPIO_PuPd_NOPULL
|
||||
},
|
||||
[BUTTON_ID_UP] = {
|
||||
"Up", GPIOG, GPIO_Pin_3, { EXTI_PortSourceGPIOG, 3 }, GPIO_PuPd_UP
|
||||
},
|
||||
[BUTTON_ID_SELECT] = {
|
||||
"Select", GPIOG, GPIO_Pin_1, { EXTI_PortSourceGPIOG, 1 }, GPIO_PuPd_UP
|
||||
},
|
||||
[BUTTON_ID_DOWN] = {
|
||||
"Down", GPIOG, GPIO_Pin_2, { EXTI_PortSourceGPIOG, 2 }, GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
|
||||
.button_com = { 0 },
|
||||
.active_high = false,
|
||||
};
|
||||
|
||||
static const BoardConfigPower BOARD_CONFIG_POWER = {
|
||||
.pmic_int = { EXTI_PortSourceGPIOG, 7 },
|
||||
.pmic_int_gpio = {
|
||||
.gpio = GPIOG,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
},
|
||||
|
||||
.rail_4V5_ctrl = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
.active_high = true,
|
||||
},
|
||||
.rail_6V6_ctrl = {
|
||||
.gpio = GPIOF,
|
||||
.gpio_pin = GPIO_Pin_3,
|
||||
.active_high = true,
|
||||
},
|
||||
|
||||
.battery_vmon_scale = {
|
||||
// The PMIC divides the battery voltage by a ratio of 3:1 in order to move it down to a voltage
|
||||
// our ADC is capable of reading. The battery voltage varies around 4V~ and we're only capable
|
||||
// of reading up to 1.8V in the ADC.
|
||||
.numerator = 3,
|
||||
.denominator = 1,
|
||||
},
|
||||
|
||||
.vusb_stat = { .gpio = GPIO_Port_NULL, },
|
||||
.chg_stat = { GPIO_Port_NULL },
|
||||
.chg_fast = { GPIO_Port_NULL },
|
||||
.chg_en = { GPIO_Port_NULL },
|
||||
.has_vusb_interrupt = false,
|
||||
|
||||
.wake_on_usb_power = false,
|
||||
|
||||
.charging_cutoff_voltage = 4300,
|
||||
.charging_status_led_voltage_compensation = 0,
|
||||
|
||||
.low_power_threshold = 7,
|
||||
.battery_capacity_hours = 44,
|
||||
};
|
||||
|
||||
static const BoardConfigAccel BOARD_CONFIG_ACCEL = {
|
||||
.accel_config = {
|
||||
.axes_offsets[AXIS_X] = 0,
|
||||
.axes_offsets[AXIS_Y] = 1,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = false,
|
||||
.shake_thresholds[AccelThresholdHigh] = 0x64,
|
||||
.shake_thresholds[AccelThresholdLow] = 0xf,
|
||||
.double_tap_threshold = 12500,
|
||||
},
|
||||
.accel_int_gpios = {
|
||||
[0] = { GPIOG, GPIO_Pin_5 },
|
||||
[1] = { GPIOG, GPIO_Pin_6 },
|
||||
},
|
||||
.accel_ints = {
|
||||
[0] = { EXTI_PortSourceGPIOG, 5 },
|
||||
[1] = { EXTI_PortSourceGPIOG, 6 }
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMag BOARD_CONFIG_MAG = {
|
||||
.mag_config = {
|
||||
.axes_offsets[AXIS_X] = 0,
|
||||
.axes_offsets[AXIS_Y] = 1,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = false,
|
||||
},
|
||||
.mag_int_gpio = { GPIOF, GPIO_Pin_14 },
|
||||
.mag_int = { EXTI_PortSourceGPIOF, 14 },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_VIBE = {
|
||||
.options = ActuatorOptions_Ctl | ActuatorOptions_Pwm | ActuatorOptions_HBridge,
|
||||
.ctl = { GPIOF, GPIO_Pin_4, true },
|
||||
.pwm = {
|
||||
.output = { GPIOB, GPIO_Pin_8, true },
|
||||
.timer = {
|
||||
.peripheral = TIM10,
|
||||
.config_clock = RCC_APB2Periph_TIM10,
|
||||
.init = TIM_OC1Init,
|
||||
.preload = TIM_OC1PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOB, GPIO_Pin_8, GPIO_PinSource8, GPIO_AF_TIM10 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_BACKLIGHT = {
|
||||
.options = ActuatorOptions_Pwm,
|
||||
.ctl = {0},
|
||||
.pwm = {
|
||||
.output = { GPIOB, GPIO_Pin_14, true },
|
||||
.timer = {
|
||||
.peripheral = TIM12,
|
||||
.config_clock = RCC_APB1Periph_TIM12,
|
||||
.init = TIM_OC1Init,
|
||||
.preload = TIM_OC1PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOB, GPIO_Pin_14, GPIO_PinSource14, GPIO_AF_TIM12 },
|
||||
},
|
||||
};
|
||||
|
||||
#define ACCESSORY_DMA_CONTROLLER DMA1_CONTROLLER
|
||||
static const BoardConfigAccessory BOARD_CONFIG_ACCESSORY = {
|
||||
.power_en = { GPIOF, GPIO_Pin_13, true },
|
||||
.int_gpio = { GPIOE, GPIO_Pin_0 },
|
||||
.exti = { EXTI_PortSourceGPIOE, 0 },
|
||||
};
|
||||
|
||||
#define BOARD_BT_USART_IRQ_HANDLER USART1_IRQHandler
|
||||
static const BoardConfigBTCommon BOARD_CONFIG_BT_COMMON = {
|
||||
.controller = CC2564B,
|
||||
.shutdown = { GPIOB, GPIO_Pin_12, false },
|
||||
.wakeup = {
|
||||
.int_gpio = { GPIOA, GPIO_Pin_11 },
|
||||
.int_exti = { EXTI_PortSourceGPIOA, 11 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMCO1 BOARD_CONFIG_MCO1 = {
|
||||
.output_enabled = true,
|
||||
.af_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_MCO,
|
||||
},
|
||||
.an_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
},
|
||||
};
|
||||
|
||||
extern DMARequest * const COMPOSITOR_DMA;
|
||||
extern DMARequest * const MIC_I2S_RX_DMA;
|
||||
|
||||
extern UARTDevice * const QEMU_UART;
|
||||
extern UARTDevice * const DBG_UART;
|
||||
extern UARTDevice * const ACCESSORY_UART;
|
||||
|
||||
extern SPISlavePort * const BMI160_SPI;
|
||||
|
||||
extern I2CSlavePort * const I2C_MAG3110;
|
||||
extern I2CSlavePort * const I2C_MAX14690;
|
||||
extern I2CSlavePort * const I2C_MFI;
|
||||
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS;
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY;
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_TEMPERATURE;
|
||||
|
||||
extern const TemperatureSensor * const TEMPERATURE_SENSOR;
|
||||
|
||||
static MicDevice * const MIC = (void *)0;
|
||||
|
||||
extern ICE40LPDevice * const ICE40LP;
|
241
src/fw/board/boards/board_v1_5.c
Normal file
241
src/fw/board/boards/board_v1_5.c
Normal 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 "board/board.h"
|
||||
|
||||
#include "drivers/i2c_definitions.h"
|
||||
#include "drivers/stm32f2/dma_definitions.h"
|
||||
#include "drivers/stm32f2/i2c_hal_definitions.h"
|
||||
#include "drivers/stm32f2/uart_definitions.h"
|
||||
#include "drivers/voltage_monitor.h"
|
||||
|
||||
// DMA Controllers
|
||||
|
||||
static DMAControllerState s_dma1_state;
|
||||
static DMAController DMA1_DEVICE = {
|
||||
.state = &s_dma1_state,
|
||||
.periph = DMA1,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA1,
|
||||
};
|
||||
|
||||
static DMAControllerState s_dma2_state;
|
||||
static DMAController DMA2_DEVICE = {
|
||||
.state = &s_dma2_state,
|
||||
.periph = DMA2,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA2,
|
||||
};
|
||||
|
||||
// DMA Streams
|
||||
|
||||
CREATE_DMA_STREAM(1, 1); // DMA1_STREAM1_DEVICE - Debug UART RX
|
||||
CREATE_DMA_STREAM(1, 4); // DMA1_STREAM4_DEVICE - Sharp SPI TX
|
||||
|
||||
// DMA Requests
|
||||
|
||||
static DMARequestState s_dbg_uart_dma_request_state;
|
||||
static DMARequest DBG_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_dbg_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM1_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_sharp_spi_tx_dma_request_state;
|
||||
static DMARequest SHARP_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_sharp_spi_tx_dma_request_state,
|
||||
.stream = &DMA1_STREAM4_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
DMARequest * const SHARP_SPI_TX_DMA = &SHARP_SPI_TX_DMA_REQUEST;
|
||||
|
||||
|
||||
// UART DEVICES
|
||||
|
||||
#if TARGET_QEMU
|
||||
static UARTDeviceState s_qemu_uart_state;
|
||||
static UARTDevice QEMU_UART_DEVICE = {
|
||||
.state = &s_qemu_uart_state,
|
||||
// GPIO? Where we're going, we don't need GPIO. (connected to QEMU)
|
||||
.periph = USART2,
|
||||
.irq_channel = USART2_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2
|
||||
};
|
||||
UARTDevice * const QEMU_UART = &QEMU_UART_DEVICE;
|
||||
IRQ_MAP(USART2, uart_irq_handler, QEMU_UART);
|
||||
#endif
|
||||
|
||||
static UARTDeviceState s_dbg_uart_state;
|
||||
static UARTDevice DBG_UART_DEVICE = {
|
||||
.state = &s_dbg_uart_state,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOD,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.rx_gpio = {
|
||||
.gpio = GPIOD,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
.gpio_pin_source = GPIO_PinSource9,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.periph = USART3,
|
||||
.irq_channel = USART3_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART3,
|
||||
.rx_dma = &DBG_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const DBG_UART = &DBG_UART_DEVICE;
|
||||
IRQ_MAP(USART3, uart_irq_handler, DBG_UART);
|
||||
|
||||
|
||||
// I2C DEVICES
|
||||
|
||||
static I2CBusState I2C_MAIN_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_MAIN_BUS_HAL = {
|
||||
.i2c = I2C1,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C1,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_16_9,
|
||||
.ev_irq_channel = I2C1_EV_IRQn,
|
||||
.er_irq_channel = I2C1_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_MAIN_BUS = {
|
||||
.state = &I2C_MAIN_BUS_STATE,
|
||||
.hal = &I2C_MAIN_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C1,
|
||||
.name = "I2C_MAIN"
|
||||
};
|
||||
|
||||
extern void i2c_rail_ctl_pin(I2CBus *device, bool enable);
|
||||
|
||||
static I2CBusState I2C_2V5_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_2V5_BUS_HAL = {
|
||||
.i2c = I2C2,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C2,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_2,
|
||||
.ev_irq_channel = I2C2_EV_IRQn,
|
||||
.er_irq_channel = I2C2_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_2V5_BUS = {
|
||||
.state = &I2C_2V5_BUS_STATE,
|
||||
.hal = &I2C_2V5_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C2,
|
||||
.rail_gpio = {
|
||||
.gpio = GPIOH,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
.active_high = true
|
||||
},
|
||||
.rail_ctl_fn = i2c_rail_ctl_pin,
|
||||
.name = "I2C_2V5"
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_LIS3DH = {
|
||||
.bus = &I2C_MAIN_BUS,
|
||||
.address = 0x32
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MFI = {
|
||||
.bus = &I2C_2V5_BUS,
|
||||
.address = 0x20
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAG3110 = {
|
||||
.bus = &I2C_2V5_BUS,
|
||||
.address = 0x1C
|
||||
};
|
||||
|
||||
I2CSlavePort * const I2C_LIS3DH = &I2C_SLAVE_LIS3DH;
|
||||
I2CSlavePort * const I2C_MFI = &I2C_SLAVE_MFI;
|
||||
I2CSlavePort * const I2C_MAG3110 = &I2C_SLAVE_MAG3110;
|
||||
|
||||
IRQ_MAP(I2C1_EV, i2c_hal_event_irq_handler, &I2C_MAIN_BUS);
|
||||
IRQ_MAP(I2C1_ER, i2c_hal_error_irq_handler, &I2C_MAIN_BUS);
|
||||
IRQ_MAP(I2C2_EV, i2c_hal_event_irq_handler, &I2C_2V5_BUS);
|
||||
IRQ_MAP(I2C2_ER, i2c_hal_error_irq_handler, &I2C_2V5_BUS);
|
||||
|
||||
|
||||
// VOLTAGE MONITOR DEVICES
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_ALS_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_12,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_BATTERY_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_10,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
},
|
||||
};
|
||||
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS = &VOLTAGE_MONITOR_ALS_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY = &VOLTAGE_MONITOR_BATTERY_DEVICE;
|
||||
|
||||
void board_early_init(void) {
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
i2c_init(&I2C_MAIN_BUS);
|
||||
i2c_init(&I2C_2V5_BUS);
|
||||
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_ALS);
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_BATTERY);
|
||||
}
|
176
src/fw/board/boards/board_v1_5.h
Normal file
176
src/fw/board/boards/board_v1_5.h
Normal file
|
@ -0,0 +1,176 @@
|
|||
/*
|
||||
* 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/battery.h"
|
||||
#include "drivers/button.h"
|
||||
#include "drivers/imu/mag3110/mag3110.h"
|
||||
#include "drivers/imu/lis3dh/lis3dh.h"
|
||||
#include "services/imu/units.h"
|
||||
#include "util/size.h"
|
||||
|
||||
#define BOARD_LSE_MODE RCC_LSE_ON
|
||||
|
||||
static const BoardConfig BOARD_CONFIG = {
|
||||
.ambient_light_dark_threshold = 3120,
|
||||
.ambient_k_delta_threshold = 96,
|
||||
.photo_en = { GPIOD, GPIO_Pin_2, true },
|
||||
|
||||
.dbgserial_int = { EXTI_PortSourceGPIOC, 11 },
|
||||
|
||||
.lcd_com = { GPIOB, GPIO_Pin_1, true },
|
||||
|
||||
.power_5v0_options = OptionActiveLowOpenDrain,
|
||||
.power_ctl_5v0 = { GPIOC, GPIO_Pin_5, false },
|
||||
|
||||
.backlight_on_percent = 25,
|
||||
.backlight_max_duty_cycle_percent = 100,
|
||||
|
||||
.has_mic = false,
|
||||
};
|
||||
|
||||
static const BoardConfigButton BOARD_CONFIG_BUTTON = {
|
||||
.buttons = {
|
||||
[BUTTON_ID_BACK] = { "Back", GPIOC, GPIO_Pin_3, { EXTI_PortSourceGPIOC, 3 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_UP] = { "Up", GPIOA, GPIO_Pin_2, { EXTI_PortSourceGPIOA, 2 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_SELECT] = { "Select", GPIOC, GPIO_Pin_6, { EXTI_PortSourceGPIOC, 6 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_DOWN] = { "Down", GPIOA, GPIO_Pin_1, { EXTI_PortSourceGPIOA, 1 }, GPIO_PuPd_NOPULL },
|
||||
},
|
||||
|
||||
.button_com = { GPIOA, GPIO_Pin_0 },
|
||||
.active_high = false,
|
||||
};
|
||||
|
||||
static const BoardConfigPower BOARD_CONFIG_POWER = {
|
||||
.vusb_stat = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_13,
|
||||
},
|
||||
.vusb_exti = { EXTI_PortSourceGPIOC, 13 },
|
||||
.chg_stat = { GPIOH, GPIO_Pin_1 },
|
||||
.chg_fast = { GPIOB, GPIO_Pin_6 },
|
||||
.chg_en = { GPIOB, GPIO_Pin_9 },
|
||||
|
||||
.has_vusb_interrupt = true,
|
||||
|
||||
.wake_on_usb_power = true,
|
||||
|
||||
.charging_status_led_voltage_compensation = 0,
|
||||
|
||||
.low_power_threshold = 3,
|
||||
.battery_capacity_hours = 144,
|
||||
};
|
||||
|
||||
static const BoardConfigAccel BOARD_CONFIG_ACCEL = {
|
||||
.accel_config = {
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = true,
|
||||
.axes_inverts[AXIS_Y] = false,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
.shake_thresholds[AccelThresholdHigh] = 0x7f,
|
||||
.shake_thresholds[AccelThresholdLow] = 0xa,
|
||||
},
|
||||
.accel_ints = {
|
||||
[0] = { EXTI_PortSourceGPIOC, 8 },
|
||||
[1] = { EXTI_PortSourceGPIOC, 9 }
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMag BOARD_CONFIG_MAG = {
|
||||
.mag_config = { // align raw mag data with accel coords (ENU)
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
},
|
||||
|
||||
.mag_int = { EXTI_PortSourceGPIOC, 4 },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_VIBE = {
|
||||
.options = ActuatorOptions_Ctl,
|
||||
.ctl = { GPIOB, GPIO_Pin_0, true },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_BACKLIGHT = {
|
||||
.options = ActuatorOptions_Pwm,
|
||||
.ctl = {0},
|
||||
.pwm = {
|
||||
.output = { GPIOB, GPIO_Pin_5, true },
|
||||
.timer = {
|
||||
.peripheral = TIM3,
|
||||
.config_clock = RCC_APB1Periph_TIM3,
|
||||
.init = TIM_OC2Init,
|
||||
.preload = TIM_OC2PreloadConfig
|
||||
},
|
||||
.afcfg = { GPIOB, GPIO_Pin_5, GPIO_PinSource5, GPIO_AF_TIM3 },
|
||||
},
|
||||
};
|
||||
|
||||
#define BOARD_BT_USART_IRQ_HANDLER USART1_IRQHandler
|
||||
static const BoardConfigBTCommon BOARD_CONFIG_BT_COMMON = {
|
||||
.controller = CC2564A,
|
||||
.shutdown = { GPIOA, GPIO_Pin_3, false},
|
||||
.wakeup = {
|
||||
.int_gpio = { GPIOC, GPIO_Pin_12 },
|
||||
.int_exti = { EXTI_PortSourceGPIOC, 12 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMCO1 BOARD_CONFIG_MCO1 = {
|
||||
.output_enabled = true,
|
||||
.af_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_MCO,
|
||||
},
|
||||
.an_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigSharpDisplay BOARD_CONFIG_DISPLAY = {
|
||||
.spi = SPI2,
|
||||
.spi_gpio = GPIOB,
|
||||
.spi_clk = RCC_APB1Periph_SPI2,
|
||||
.spi_clk_periph = SpiPeriphClockAPB1,
|
||||
|
||||
.clk = { GPIOB, GPIO_Pin_13, GPIO_PinSource13, GPIO_AF_SPI2 },
|
||||
.mosi = { GPIOB, GPIO_Pin_15, GPIO_PinSource15, GPIO_AF_SPI2 },
|
||||
.cs = { GPIOB, GPIO_Pin_12, true },
|
||||
|
||||
.on_ctrl = { GPIOB, GPIO_Pin_14, true },
|
||||
.on_ctrl_otype = GPIO_OType_OD,
|
||||
};
|
||||
|
||||
extern DMARequest * const SHARP_SPI_TX_DMA;
|
||||
|
||||
extern UARTDevice * const QEMU_UART;
|
||||
extern UARTDevice * const DBG_UART;
|
||||
|
||||
extern I2CSlavePort * const I2C_LIS3DH;
|
||||
extern I2CSlavePort * const I2C_MFI;
|
||||
extern I2CSlavePort * const I2C_MAG3110;
|
||||
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS;
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY;
|
247
src/fw/board/boards/board_v2_0.c
Normal file
247
src/fw/board/boards/board_v2_0.c
Normal file
|
@ -0,0 +1,247 @@
|
|||
/*
|
||||
* 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/i2c_definitions.h"
|
||||
#include "drivers/stm32f2/dma_definitions.h"
|
||||
#include "drivers/stm32f2/i2c_hal_definitions.h"
|
||||
#include "drivers/stm32f2/uart_definitions.h"
|
||||
#include "drivers/voltage_monitor.h"
|
||||
|
||||
// DMA Controllers
|
||||
|
||||
static DMAControllerState s_dma1_state;
|
||||
static DMAController DMA1_DEVICE = {
|
||||
.state = &s_dma1_state,
|
||||
.periph = DMA1,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA1,
|
||||
};
|
||||
|
||||
static DMAControllerState s_dma2_state;
|
||||
static DMAController DMA2_DEVICE = {
|
||||
.state = &s_dma2_state,
|
||||
.periph = DMA2,
|
||||
.rcc_bit = RCC_AHB1Periph_DMA2,
|
||||
};
|
||||
|
||||
// DMA Streams
|
||||
|
||||
CREATE_DMA_STREAM(1, 1); // DMA1_STREAM1_DEVICE - Debug UART RX
|
||||
CREATE_DMA_STREAM(1, 4); // DMA1_STREAM4_DEVICE - Sharp SPI TX
|
||||
|
||||
// DMA Requests
|
||||
|
||||
static DMARequestState s_dbg_uart_dma_request_state;
|
||||
static DMARequest DBG_UART_RX_DMA_REQUEST = {
|
||||
.state = &s_dbg_uart_dma_request_state,
|
||||
.stream = &DMA1_STREAM1_DEVICE,
|
||||
.channel = 4,
|
||||
.irq_priority = IRQ_PRIORITY_INVALID, // no interrupts
|
||||
.priority = DMARequestPriority_High,
|
||||
.type = DMARequestType_PeripheralToMemory,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
|
||||
static DMARequestState s_sharp_spi_tx_dma_request_state;
|
||||
static DMARequest SHARP_SPI_TX_DMA_REQUEST = {
|
||||
.state = &s_sharp_spi_tx_dma_request_state,
|
||||
.stream = &DMA1_STREAM4_DEVICE,
|
||||
.channel = 0,
|
||||
.irq_priority = 0x0f,
|
||||
.priority = DMARequestPriority_VeryHigh,
|
||||
.type = DMARequestType_MemoryToPeripheral,
|
||||
.data_size = DMARequestDataSize_Byte,
|
||||
};
|
||||
DMARequest * const SHARP_SPI_TX_DMA = &SHARP_SPI_TX_DMA_REQUEST;
|
||||
|
||||
|
||||
// UART DEVICES
|
||||
|
||||
#if TARGET_QEMU
|
||||
static UARTDeviceState s_qemu_uart_state;
|
||||
static UARTDevice QEMU_UART_DEVICE = {
|
||||
.state = &s_qemu_uart_state,
|
||||
// GPIO? Where we're going, we don't need GPIO. (connected to QEMU)
|
||||
.periph = USART2,
|
||||
.irq_channel = USART2_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART2
|
||||
};
|
||||
UARTDevice * const QEMU_UART = &QEMU_UART_DEVICE;
|
||||
IRQ_MAP(USART2, uart_irq_handler, QEMU_UART);
|
||||
#endif
|
||||
|
||||
static UARTDeviceState s_dbg_uart_state;
|
||||
static UARTDevice DBG_UART_DEVICE = {
|
||||
.state = &s_dbg_uart_state,
|
||||
.tx_gpio = {
|
||||
.gpio = GPIOD,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.rx_gpio = {
|
||||
.gpio = GPIOD,
|
||||
.gpio_pin = GPIO_Pin_9,
|
||||
.gpio_pin_source = GPIO_PinSource9,
|
||||
.gpio_af = GPIO_AF_USART3
|
||||
},
|
||||
.periph = USART3,
|
||||
.irq_channel = USART3_IRQn,
|
||||
.irq_priority = 13,
|
||||
.rcc_apb_periph = RCC_APB1Periph_USART3,
|
||||
.rx_dma = &DBG_UART_RX_DMA_REQUEST
|
||||
};
|
||||
UARTDevice * const DBG_UART = &DBG_UART_DEVICE;
|
||||
IRQ_MAP(USART3, uart_irq_handler, DBG_UART);
|
||||
|
||||
|
||||
// I2C DEVICES
|
||||
|
||||
static I2CBusState I2C_MAIN_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_MAIN_BUS_HAL = {
|
||||
.i2c = I2C1,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C1,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_16_9,
|
||||
.ev_irq_channel = I2C1_EV_IRQn,
|
||||
.er_irq_channel = I2C1_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_MAIN_BUS = {
|
||||
.state = &I2C_MAIN_BUS_STATE,
|
||||
.hal = &I2C_MAIN_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_7,
|
||||
.gpio_pin_source = GPIO_PinSource7,
|
||||
.gpio_af = GPIO_AF_I2C1
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C1,
|
||||
.name = "I2C_MAIN"
|
||||
};
|
||||
|
||||
extern void i2c_rail_ctl_pin(I2CBus *device, bool enable);
|
||||
|
||||
static I2CBusState I2C_2V5_BUS_STATE = {};
|
||||
|
||||
static const I2CBusHal I2C_2V5_BUS_HAL = {
|
||||
.i2c = I2C2,
|
||||
.clock_ctrl = RCC_APB1Periph_I2C2,
|
||||
.clock_speed = 400000,
|
||||
.duty_cycle = I2CDutyCycle_2,
|
||||
.ev_irq_channel = I2C2_EV_IRQn,
|
||||
.er_irq_channel = I2C2_ER_IRQn,
|
||||
};
|
||||
|
||||
static const I2CBus I2C_2V5_BUS = {
|
||||
.state = &I2C_2V5_BUS_STATE,
|
||||
.hal = &I2C_2V5_BUS_HAL,
|
||||
.scl_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_10,
|
||||
.gpio_pin_source = GPIO_PinSource10,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.sda_gpio = {
|
||||
.gpio = GPIOB,
|
||||
.gpio_pin = GPIO_Pin_11,
|
||||
.gpio_pin_source = GPIO_PinSource11,
|
||||
.gpio_af = GPIO_AF_I2C2
|
||||
},
|
||||
.stop_mode_inhibitor = InhibitorI2C2,
|
||||
.rail_gpio = {
|
||||
.gpio = GPIOH,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
.active_high = true
|
||||
},
|
||||
.rail_ctl_fn = i2c_rail_ctl_pin,
|
||||
.name = "I2C_2V5"
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_LIS3DH = {
|
||||
.bus = &I2C_MAIN_BUS,
|
||||
.address = 0x32
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MFI = {
|
||||
.bus = &I2C_2V5_BUS,
|
||||
.address = 0x20
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_MAG3110 = {
|
||||
.bus = &I2C_2V5_BUS,
|
||||
.address = 0x1C
|
||||
};
|
||||
|
||||
static const I2CSlavePort I2C_SLAVE_LED = {
|
||||
.bus = &I2C_MAIN_BUS,
|
||||
.address = 0xC8
|
||||
};
|
||||
|
||||
I2CSlavePort * const I2C_LIS3DH = &I2C_SLAVE_LIS3DH;
|
||||
I2CSlavePort * const I2C_MFI = &I2C_SLAVE_MFI;
|
||||
I2CSlavePort * const I2C_MAG3110 = &I2C_SLAVE_MAG3110;
|
||||
I2CSlavePort * const I2C_LED = &I2C_SLAVE_LED;
|
||||
|
||||
IRQ_MAP(I2C1_EV, i2c_hal_event_irq_handler, &I2C_MAIN_BUS);
|
||||
IRQ_MAP(I2C1_ER, i2c_hal_error_irq_handler, &I2C_MAIN_BUS);
|
||||
IRQ_MAP(I2C2_EV, i2c_hal_event_irq_handler, &I2C_2V5_BUS);
|
||||
IRQ_MAP(I2C2_ER, i2c_hal_error_irq_handler, &I2C_2V5_BUS);
|
||||
|
||||
|
||||
// VOLTAGE MONITOR DEVICES
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_ALS_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_12,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_2,
|
||||
},
|
||||
};
|
||||
|
||||
static const VoltageMonitorDevice VOLTAGE_MONITOR_BATTERY_DEVICE = {
|
||||
.adc = ADC2,
|
||||
.adc_channel = ADC_Channel_10,
|
||||
.clock_ctrl = RCC_APB2Periph_ADC2,
|
||||
.input = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_0,
|
||||
},
|
||||
};
|
||||
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS = &VOLTAGE_MONITOR_ALS_DEVICE;
|
||||
VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY = &VOLTAGE_MONITOR_BATTERY_DEVICE;
|
||||
|
||||
void board_early_init(void) {
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
i2c_init(&I2C_MAIN_BUS);
|
||||
i2c_init(&I2C_2V5_BUS);
|
||||
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_ALS);
|
||||
voltage_monitor_device_init(VOLTAGE_MONITOR_BATTERY);
|
||||
}
|
164
src/fw/board/boards/board_v2_0.h
Normal file
164
src/fw/board/boards/board_v2_0.h
Normal file
|
@ -0,0 +1,164 @@
|
|||
/*
|
||||
* 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/battery.h"
|
||||
#include "drivers/button.h"
|
||||
#include "services/imu/units.h"
|
||||
#include "util/size.h"
|
||||
|
||||
#include "drivers/imu/mag3110/mag3110.h"
|
||||
#include "drivers/imu/lis3dh/lis3dh.h"
|
||||
|
||||
#define BOARD_LSE_MODE RCC_LSE_ON
|
||||
|
||||
static const BoardConfig BOARD_CONFIG = {
|
||||
.ambient_light_dark_threshold = 3200,
|
||||
.ambient_k_delta_threshold = 96,
|
||||
.photo_en = { GPIOD, GPIO_Pin_2, true },
|
||||
|
||||
.dbgserial_int = { EXTI_PortSourceGPIOC, 11 },
|
||||
|
||||
.power_ctl_5v0 = { GPIOC, GPIO_Pin_5, false },
|
||||
.lcd_com = { GPIOB, GPIO_Pin_1, true },
|
||||
|
||||
.backlight_on_percent = 100,
|
||||
.backlight_max_duty_cycle_percent = 100,
|
||||
.power_5v0_options = OptionActiveLowOpenDrain,
|
||||
|
||||
.has_mic = false,
|
||||
};
|
||||
|
||||
static const BoardConfigButton BOARD_CONFIG_BUTTON = {
|
||||
.buttons = {
|
||||
[BUTTON_ID_BACK] = { "Back", GPIOC, GPIO_Pin_3, { EXTI_PortSourceGPIOC, 3 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_UP] = { "Up", GPIOA, GPIO_Pin_2, { EXTI_PortSourceGPIOA, 2 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_SELECT] = { "Select", GPIOC, GPIO_Pin_6, { EXTI_PortSourceGPIOC, 6 }, GPIO_PuPd_NOPULL },
|
||||
[BUTTON_ID_DOWN] = { "Down", GPIOA, GPIO_Pin_1, { EXTI_PortSourceGPIOA, 1 }, GPIO_PuPd_NOPULL },
|
||||
},
|
||||
|
||||
.button_com = { GPIOA, GPIO_Pin_0 },
|
||||
.active_high = false,
|
||||
};
|
||||
|
||||
static const BoardConfigPower BOARD_CONFIG_POWER = {
|
||||
.vusb_stat = {
|
||||
.gpio = GPIOC,
|
||||
.gpio_pin = GPIO_Pin_13,
|
||||
},
|
||||
.vusb_exti = { EXTI_PortSourceGPIOC, 13 },
|
||||
.chg_stat = { GPIOH, GPIO_Pin_1 },
|
||||
.chg_fast = { GPIOB, GPIO_Pin_6 },
|
||||
.chg_en = { GPIOB, GPIO_Pin_9 },
|
||||
|
||||
.has_vusb_interrupt = true,
|
||||
|
||||
.charging_status_led_voltage_compensation = 30,
|
||||
|
||||
.low_power_threshold = 6,
|
||||
.battery_capacity_hours = 144,
|
||||
};
|
||||
|
||||
static const BoardConfigAccel BOARD_CONFIG_ACCEL = {
|
||||
.accel_config = {
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = true,
|
||||
.axes_inverts[AXIS_Y] = false,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
.shake_thresholds[AccelThresholdHigh] = 0x7f,
|
||||
.shake_thresholds[AccelThresholdLow] = 0xa,
|
||||
},
|
||||
.accel_ints = {
|
||||
[0] = { EXTI_PortSourceGPIOC, 8 },
|
||||
[1] = { EXTI_PortSourceGPIOC, 9 }
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMag BOARD_CONFIG_MAG = {
|
||||
.mag_config = { // align raw mag data with accel coords (ENU)
|
||||
.axes_offsets[AXIS_X] = 1,
|
||||
.axes_offsets[AXIS_Y] = 0,
|
||||
.axes_offsets[AXIS_Z] = 2,
|
||||
.axes_inverts[AXIS_X] = false,
|
||||
.axes_inverts[AXIS_Y] = true,
|
||||
.axes_inverts[AXIS_Z] = true,
|
||||
},
|
||||
.mag_int = { EXTI_PortSourceGPIOC, 4 },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_VIBE = {
|
||||
.options = ActuatorOptions_Ctl,
|
||||
.ctl = { GPIOB, GPIO_Pin_0, true },
|
||||
};
|
||||
|
||||
static const BoardConfigActuator BOARD_CONFIG_BACKLIGHT = {
|
||||
.options = ActuatorOptions_IssiI2C,
|
||||
.ctl = { GPIOB, GPIO_Pin_5, true },
|
||||
};
|
||||
|
||||
#define BOARD_BT_USART_IRQ_HANDLER USART1_IRQHandler
|
||||
static const BoardConfigBTCommon BOARD_CONFIG_BT_COMMON = {
|
||||
.controller = CC2564A,
|
||||
.shutdown = { GPIOA, GPIO_Pin_3, false},
|
||||
.wakeup = {
|
||||
.int_gpio = { GPIOC, GPIO_Pin_12 },
|
||||
.int_exti = { EXTI_PortSourceGPIOC, 12 },
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigMCO1 BOARD_CONFIG_MCO1 = {
|
||||
.output_enabled = true,
|
||||
.af_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
.gpio_pin_source = GPIO_PinSource8,
|
||||
.gpio_af = GPIO_AF_MCO,
|
||||
},
|
||||
.an_cfg = {
|
||||
.gpio = GPIOA,
|
||||
.gpio_pin = GPIO_Pin_8,
|
||||
},
|
||||
};
|
||||
|
||||
static const BoardConfigSharpDisplay BOARD_CONFIG_DISPLAY = {
|
||||
.spi = SPI2,
|
||||
.spi_gpio = GPIOB,
|
||||
.spi_clk = RCC_APB1Periph_SPI2,
|
||||
.spi_clk_periph = SpiPeriphClockAPB1,
|
||||
|
||||
.clk = { GPIOB, GPIO_Pin_13, GPIO_PinSource13, GPIO_AF_SPI2 },
|
||||
.mosi = { GPIOB, GPIO_Pin_15, GPIO_PinSource15, GPIO_AF_SPI2 },
|
||||
.cs = { GPIOB, GPIO_Pin_12, true },
|
||||
|
||||
.on_ctrl = { GPIOB, GPIO_Pin_14, true },
|
||||
.on_ctrl_otype = GPIO_OType_OD,
|
||||
};
|
||||
|
||||
extern DMARequest * const SHARP_SPI_TX_DMA;
|
||||
|
||||
extern UARTDevice * const QEMU_UART;
|
||||
extern UARTDevice * const DBG_UART;
|
||||
|
||||
extern I2CSlavePort * const I2C_LIS3DH;
|
||||
extern I2CSlavePort * const I2C_MFI;
|
||||
extern I2CSlavePort * const I2C_MAG3110;
|
||||
extern I2CSlavePort * const I2C_LED;
|
||||
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_ALS;
|
||||
extern VoltageMonitorDevice * const VOLTAGE_MONITOR_BATTERY;
|
94
src/fw/board/display.h
Normal file
94
src/fw/board/display.h
Normal file
|
@ -0,0 +1,94 @@
|
|||
/*
|
||||
* 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>
|
||||
|
||||
//! @internal
|
||||
//! data type that's used to store row data infos in a space-efficient manner
|
||||
typedef struct {
|
||||
uint16_t offset;
|
||||
uint8_t min_x;
|
||||
uint8_t max_x;
|
||||
} GBitmapDataRowInfoInternal;
|
||||
|
||||
// FIXME: PBL-21055 Fix SDK exporter failing to crawl framebuffer headers
|
||||
#if !defined(SDK)
|
||||
|
||||
// FIXME: PBL-21049 Fix platform abstraction and board definition scheme
|
||||
#ifdef UNITTEST
|
||||
// Do nothing, a unit-test's wscript specifies platforms=[]
|
||||
// used by waftools/pebble_test.py to define these includes per test
|
||||
#else
|
||||
|
||||
#if BOARD_BIGBOARD
|
||||
#include "displays/display_tintin.h"
|
||||
#elif BOARD_EV2_4
|
||||
#include "displays/display_tintin.h"
|
||||
#elif BOARD_BB2
|
||||
#include "displays/display_tintin.h"
|
||||
#elif BOARD_V1_5
|
||||
#include "displays/display_tintin.h"
|
||||
#elif BOARD_V2_0
|
||||
#include "displays/display_tintin.h"
|
||||
#elif BOARD_SNOWY_BB
|
||||
#include "displays/display_snowy.h"
|
||||
#elif BOARD_SNOWY_EVT
|
||||
#include "displays/display_snowy.h"
|
||||
#elif BOARD_SNOWY_EVT2
|
||||
#include "displays/display_snowy.h"
|
||||
#elif BOARD_SNOWY_BB2
|
||||
#include "displays/display_snowy.h"
|
||||
#elif BOARD_SNOWY_DVT
|
||||
#include "displays/display_snowy.h"
|
||||
#elif BOARD_SNOWY_S3
|
||||
#include "displays/display_snowy.h"
|
||||
#elif BOARD_SPALDING_BB2
|
||||
#include "displays/display_spalding.h"
|
||||
#elif BOARD_SPALDING_EVT
|
||||
#include "displays/display_spalding.h"
|
||||
#elif BOARD_SPALDING
|
||||
#include "displays/display_spalding.h"
|
||||
#elif BOARD_SILK_EVT
|
||||
#include "displays/display_silk.h"
|
||||
#elif BOARD_SILK_BB
|
||||
#include "displays/display_silk.h"
|
||||
#elif BOARD_SILK_BB2
|
||||
#include "displays/display_silk.h"
|
||||
#elif BOARD_SILK
|
||||
#include "displays/display_silk.h"
|
||||
#elif BOARD_CUTTS_BB
|
||||
#include "displays/display_snowy.h"
|
||||
#elif BOARD_ROBERT_BB
|
||||
#include "displays/display_robert.h"
|
||||
#elif BOARD_ROBERT_BB2
|
||||
#include "displays/display_robert.h"
|
||||
#elif BOARD_ROBERT_EVT
|
||||
#include "displays/display_robert_evt.h"
|
||||
#else
|
||||
#error "Unknown display definition for board"
|
||||
#endif // BOARD_*
|
||||
|
||||
#endif // UNITTEST
|
||||
|
||||
// For backwards compatibility, new code should use PBL_DISPLAY_WIDTH and PBL_DISPLAY_HEIGHT
|
||||
#if !defined(DISP_COLS) || !defined(DISP_ROWS)
|
||||
#define DISP_COLS PBL_DISPLAY_WIDTH
|
||||
#define DISP_ROWS PBL_DISPLAY_HEIGHT
|
||||
#endif // DISP_COLS || DISP_ROWS
|
||||
|
||||
#endif // !SDK
|
38
src/fw/board/displays/display_robert.h
Normal file
38
src/fw/board/displays/display_robert.h
Normal 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
|
||||
|
||||
#define DISPLAY_ORIENTATION_COLUMN_MAJOR_INVERTED 0
|
||||
#define DISPLAY_ORIENTATION_ROTATED_180 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR_INVERTED 1
|
||||
|
||||
#define PBL_BW 0
|
||||
#define PBL_COLOR 1
|
||||
|
||||
#define PBL_RECT 1
|
||||
#define PBL_ROUND 0
|
||||
|
||||
#define PBL_DISPLAY_WIDTH 200
|
||||
#define PBL_DISPLAY_HEIGHT 228
|
||||
|
||||
#define LEGACY_2X_DISP_COLS 144
|
||||
#define LEGACY_2X_DISP_ROWS 168
|
||||
#define LEGACY_3X_DISP_COLS LEGACY_2X_DISP_COLS
|
||||
#define LEGACY_3X_DISP_ROWS LEGACY_2X_DISP_ROWS
|
||||
|
||||
#define DISPLAY_FRAMEBUFFER_BYTES (PBL_DISPLAY_WIDTH * PBL_DISPLAY_HEIGHT)
|
38
src/fw/board/displays/display_robert_evt.h
Normal file
38
src/fw/board/displays/display_robert_evt.h
Normal 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
|
||||
|
||||
#define DISPLAY_ORIENTATION_COLUMN_MAJOR_INVERTED 0
|
||||
#define DISPLAY_ORIENTATION_ROTATED_180 1
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR_INVERTED 1
|
||||
|
||||
#define PBL_BW 0
|
||||
#define PBL_COLOR 1
|
||||
|
||||
#define PBL_RECT 1
|
||||
#define PBL_ROUND 0
|
||||
|
||||
#define PBL_DISPLAY_WIDTH 200
|
||||
#define PBL_DISPLAY_HEIGHT 228
|
||||
|
||||
#define LEGACY_2X_DISP_COLS 144
|
||||
#define LEGACY_2X_DISP_ROWS 168
|
||||
#define LEGACY_3X_DISP_COLS LEGACY_2X_DISP_COLS
|
||||
#define LEGACY_3X_DISP_ROWS LEGACY_2X_DISP_ROWS
|
||||
|
||||
#define DISPLAY_FRAMEBUFFER_BYTES (PBL_DISPLAY_WIDTH * PBL_DISPLAY_HEIGHT)
|
39
src/fw/board/displays/display_silk.h
Normal file
39
src/fw/board/displays/display_silk.h
Normal 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.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define DISPLAY_ORIENTATION_COLUMN_MAJOR_INVERTED 0
|
||||
#define DISPLAY_ORIENTATION_ROTATED_180 1
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR_INVERTED 0
|
||||
|
||||
#define PBL_BW 1
|
||||
#define PBL_COLOR 0
|
||||
|
||||
#define PBL_RECT 1
|
||||
#define PBL_ROUND 0
|
||||
|
||||
#define PBL_DISPLAY_WIDTH 144
|
||||
#define PBL_DISPLAY_HEIGHT 168
|
||||
|
||||
#define LEGACY_2X_DISP_COLS PBL_DISPLAY_WIDTH
|
||||
#define LEGACY_2X_DISP_ROWS PBL_DISPLAY_HEIGHT
|
||||
#define LEGACY_3X_DISP_COLS PBL_DISPLAY_WIDTH
|
||||
#define LEGACY_3X_DISP_ROWS PBL_DISPLAY_HEIGHT
|
||||
|
||||
#define DISPLAY_FRAMEBUFFER_BYTES \
|
||||
(ROUND_TO_MOD_CEIL(PBL_DISPLAY_WIDTH, 32) / 8 * PBL_DISPLAY_HEIGHT)
|
38
src/fw/board/displays/display_snowy.h
Normal file
38
src/fw/board/displays/display_snowy.h
Normal 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
|
||||
|
||||
#define DISPLAY_ORIENTATION_COLUMN_MAJOR_INVERTED 1
|
||||
#define DISPLAY_ORIENTATION_ROTATED_180 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR_INVERTED 0
|
||||
|
||||
#define PBL_BW 0
|
||||
#define PBL_COLOR 1
|
||||
|
||||
#define PBL_RECT 1
|
||||
#define PBL_ROUND 0
|
||||
|
||||
#define PBL_DISPLAY_WIDTH 144
|
||||
#define PBL_DISPLAY_HEIGHT 168
|
||||
|
||||
#define LEGACY_2X_DISP_COLS DISP_COLS
|
||||
#define LEGACY_2X_DISP_ROWS DISP_ROWS
|
||||
#define LEGACY_3X_DISP_COLS DISP_COLS
|
||||
#define LEGACY_3X_DISP_ROWS DISP_ROWS
|
||||
|
||||
#define DISPLAY_FRAMEBUFFER_BYTES (PBL_DISPLAY_WIDTH * PBL_DISPLAY_HEIGHT)
|
242
src/fw/board/displays/display_spalding.c
Normal file
242
src/fw/board/displays/display_spalding.c
Normal file
|
@ -0,0 +1,242 @@
|
|||
/*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
// Spalding display pixel masks
|
||||
//
|
||||
// The Spalding round display is logically a square 180x180 display with
|
||||
// some of the pixels hidden under a mask or missing entirely. The mask
|
||||
// is symmetrical both horizontally and vertically: the masks on the
|
||||
// left and right side of a line are equal, and the mask on the top half
|
||||
// of the display is a mirror image of the bottom half.
|
||||
//
|
||||
// This array maps the number of pixels masked off for one quadrant of
|
||||
// the display. Array element zero is the number of masked pixels from
|
||||
// a display corner inwards. Subsequent array elements contain the mask
|
||||
// for the adjacent rows or columns moving inwards towards the center
|
||||
// of the display.
|
||||
|
||||
#include "board/display.h"
|
||||
|
||||
// g_gbitmap_spalding_data_row_infos was generated with this script:
|
||||
//
|
||||
// #!/bin/env python
|
||||
// topleft_mask = [ 76, 71, 66, 63, 60, 57, 55, 52, 50, 48, 46, 45, 43, 41, 40, 38, 37,
|
||||
// 36, 34, 33, 32, 31, 29, 28, 27, 26, 25, 24, 23, 22, 22, 21, 20, 19,
|
||||
// 18, 18, 17, 16, 15, 15, 14, 13, 13, 12, 12, 11, 10, 10, 9, 9, 8, 8, 7,
|
||||
// 7, 7, 6, 6, 5, 5, 5, 4, 4, 4, 3, 3, 3, 2, 2, 2, 2, 2, 1, 1, 1, 1, 1,
|
||||
// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
|
||||
//
|
||||
// offset = 76 #pad the offset with 76 so we don't underflow on the first row
|
||||
// for i in range(0, 180):
|
||||
// if (i < 90):
|
||||
// min_x = topleft_mask[i]
|
||||
// else :
|
||||
// min_x = topleft_mask[180 - i - 1]
|
||||
//
|
||||
// width = 90 - min_x
|
||||
// max_x = 180 - min_x - 1
|
||||
// #individual rows are the current offset minus the min_y to get to the first usable byte
|
||||
// print(" /" + "* y = %3d */ {.offset = %5d, .min_x = %2d, .max_x = %3d}," %
|
||||
// (i, offset - min_x, min_x, max_x))
|
||||
// # total offset is usable bytes in the row, so accumulate that
|
||||
// offset += (max_x - min_x + 1)
|
||||
//
|
||||
// # pad the size of the buffer before and after by 76 bytes so
|
||||
// # framebuffer row reads are never accessing memory beyond buffer
|
||||
// print ("Circular Framebuffer has %d bytes" % (offset + topleft_mask[0]))
|
||||
|
||||
const void * const g_gbitmap_spalding_data_row_infos = (const GBitmapDataRowInfoInternal[]) {
|
||||
/* y = 0 */ {.offset = 0, .min_x = 76, .max_x = 103},
|
||||
/* y = 1 */ {.offset = 33, .min_x = 71, .max_x = 108},
|
||||
/* y = 2 */ {.offset = 76, .min_x = 66, .max_x = 113},
|
||||
/* y = 3 */ {.offset = 127, .min_x = 63, .max_x = 116},
|
||||
/* y = 4 */ {.offset = 184, .min_x = 60, .max_x = 119},
|
||||
/* y = 5 */ {.offset = 247, .min_x = 57, .max_x = 122},
|
||||
/* y = 6 */ {.offset = 315, .min_x = 55, .max_x = 124},
|
||||
/* y = 7 */ {.offset = 388, .min_x = 52, .max_x = 127},
|
||||
/* y = 8 */ {.offset = 466, .min_x = 50, .max_x = 129},
|
||||
/* y = 9 */ {.offset = 548, .min_x = 48, .max_x = 131},
|
||||
/* y = 10 */ {.offset = 634, .min_x = 46, .max_x = 133},
|
||||
/* y = 11 */ {.offset = 723, .min_x = 45, .max_x = 134},
|
||||
/* y = 12 */ {.offset = 815, .min_x = 43, .max_x = 136},
|
||||
/* y = 13 */ {.offset = 911, .min_x = 41, .max_x = 138},
|
||||
/* y = 14 */ {.offset = 1010, .min_x = 40, .max_x = 139},
|
||||
/* y = 15 */ {.offset = 1112, .min_x = 38, .max_x = 141},
|
||||
/* y = 16 */ {.offset = 1217, .min_x = 37, .max_x = 142},
|
||||
/* y = 17 */ {.offset = 1324, .min_x = 36, .max_x = 143},
|
||||
/* y = 18 */ {.offset = 1434, .min_x = 34, .max_x = 145},
|
||||
/* y = 19 */ {.offset = 1547, .min_x = 33, .max_x = 146},
|
||||
/* y = 20 */ {.offset = 1662, .min_x = 32, .max_x = 147},
|
||||
/* y = 21 */ {.offset = 1779, .min_x = 31, .max_x = 148},
|
||||
/* y = 22 */ {.offset = 1899, .min_x = 29, .max_x = 150},
|
||||
/* y = 23 */ {.offset = 2022, .min_x = 28, .max_x = 151},
|
||||
/* y = 24 */ {.offset = 2147, .min_x = 27, .max_x = 152},
|
||||
/* y = 25 */ {.offset = 2274, .min_x = 26, .max_x = 153},
|
||||
/* y = 26 */ {.offset = 2403, .min_x = 25, .max_x = 154},
|
||||
/* y = 27 */ {.offset = 2534, .min_x = 24, .max_x = 155},
|
||||
/* y = 28 */ {.offset = 2667, .min_x = 23, .max_x = 156},
|
||||
/* y = 29 */ {.offset = 2802, .min_x = 22, .max_x = 157},
|
||||
/* y = 30 */ {.offset = 2938, .min_x = 22, .max_x = 157},
|
||||
/* y = 31 */ {.offset = 3075, .min_x = 21, .max_x = 158},
|
||||
/* y = 32 */ {.offset = 3214, .min_x = 20, .max_x = 159},
|
||||
/* y = 33 */ {.offset = 3355, .min_x = 19, .max_x = 160},
|
||||
/* y = 34 */ {.offset = 3498, .min_x = 18, .max_x = 161},
|
||||
/* y = 35 */ {.offset = 3642, .min_x = 18, .max_x = 161},
|
||||
/* y = 36 */ {.offset = 3787, .min_x = 17, .max_x = 162},
|
||||
/* y = 37 */ {.offset = 3934, .min_x = 16, .max_x = 163},
|
||||
/* y = 38 */ {.offset = 4083, .min_x = 15, .max_x = 164},
|
||||
/* y = 39 */ {.offset = 4233, .min_x = 15, .max_x = 164},
|
||||
/* y = 40 */ {.offset = 4384, .min_x = 14, .max_x = 165},
|
||||
/* y = 41 */ {.offset = 4537, .min_x = 13, .max_x = 166},
|
||||
/* y = 42 */ {.offset = 4691, .min_x = 13, .max_x = 166},
|
||||
/* y = 43 */ {.offset = 4846, .min_x = 12, .max_x = 167},
|
||||
/* y = 44 */ {.offset = 5002, .min_x = 12, .max_x = 167},
|
||||
/* y = 45 */ {.offset = 5159, .min_x = 11, .max_x = 168},
|
||||
/* y = 46 */ {.offset = 5318, .min_x = 10, .max_x = 169},
|
||||
/* y = 47 */ {.offset = 5478, .min_x = 10, .max_x = 169},
|
||||
/* y = 48 */ {.offset = 5639, .min_x = 9, .max_x = 170},
|
||||
/* y = 49 */ {.offset = 5801, .min_x = 9, .max_x = 170},
|
||||
/* y = 50 */ {.offset = 5964, .min_x = 8, .max_x = 171},
|
||||
/* y = 51 */ {.offset = 6128, .min_x = 8, .max_x = 171},
|
||||
/* y = 52 */ {.offset = 6293, .min_x = 7, .max_x = 172},
|
||||
/* y = 53 */ {.offset = 6459, .min_x = 7, .max_x = 172},
|
||||
/* y = 54 */ {.offset = 6625, .min_x = 7, .max_x = 172},
|
||||
/* y = 55 */ {.offset = 6792, .min_x = 6, .max_x = 173},
|
||||
/* y = 56 */ {.offset = 6960, .min_x = 6, .max_x = 173},
|
||||
/* y = 57 */ {.offset = 7129, .min_x = 5, .max_x = 174},
|
||||
/* y = 58 */ {.offset = 7299, .min_x = 5, .max_x = 174},
|
||||
/* y = 59 */ {.offset = 7469, .min_x = 5, .max_x = 174},
|
||||
/* y = 60 */ {.offset = 7640, .min_x = 4, .max_x = 175},
|
||||
/* y = 61 */ {.offset = 7812, .min_x = 4, .max_x = 175},
|
||||
/* y = 62 */ {.offset = 7984, .min_x = 4, .max_x = 175},
|
||||
/* y = 63 */ {.offset = 8157, .min_x = 3, .max_x = 176},
|
||||
/* y = 64 */ {.offset = 8331, .min_x = 3, .max_x = 176},
|
||||
/* y = 65 */ {.offset = 8505, .min_x = 3, .max_x = 176},
|
||||
/* y = 66 */ {.offset = 8680, .min_x = 2, .max_x = 177},
|
||||
/* y = 67 */ {.offset = 8856, .min_x = 2, .max_x = 177},
|
||||
/* y = 68 */ {.offset = 9032, .min_x = 2, .max_x = 177},
|
||||
/* y = 69 */ {.offset = 9208, .min_x = 2, .max_x = 177},
|
||||
/* y = 70 */ {.offset = 9384, .min_x = 2, .max_x = 177},
|
||||
/* y = 71 */ {.offset = 9561, .min_x = 1, .max_x = 178},
|
||||
/* y = 72 */ {.offset = 9739, .min_x = 1, .max_x = 178},
|
||||
/* y = 73 */ {.offset = 9917, .min_x = 1, .max_x = 178},
|
||||
/* y = 74 */ {.offset = 10095, .min_x = 1, .max_x = 178},
|
||||
/* y = 75 */ {.offset = 10273, .min_x = 1, .max_x = 178},
|
||||
/* y = 76 */ {.offset = 10452, .min_x = 0, .max_x = 179},
|
||||
/* y = 77 */ {.offset = 10632, .min_x = 0, .max_x = 179},
|
||||
/* y = 78 */ {.offset = 10812, .min_x = 0, .max_x = 179},
|
||||
/* y = 79 */ {.offset = 10992, .min_x = 0, .max_x = 179},
|
||||
/* y = 80 */ {.offset = 11172, .min_x = 0, .max_x = 179},
|
||||
/* y = 81 */ {.offset = 11352, .min_x = 0, .max_x = 179},
|
||||
/* y = 82 */ {.offset = 11532, .min_x = 0, .max_x = 179},
|
||||
/* y = 83 */ {.offset = 11712, .min_x = 0, .max_x = 179},
|
||||
/* y = 84 */ {.offset = 11892, .min_x = 0, .max_x = 179},
|
||||
/* y = 85 */ {.offset = 12072, .min_x = 0, .max_x = 179},
|
||||
/* y = 86 */ {.offset = 12252, .min_x = 0, .max_x = 179},
|
||||
/* y = 87 */ {.offset = 12432, .min_x = 0, .max_x = 179},
|
||||
/* y = 88 */ {.offset = 12612, .min_x = 0, .max_x = 179},
|
||||
/* y = 89 */ {.offset = 12792, .min_x = 0, .max_x = 179},
|
||||
/* y = 90 */ {.offset = 12972, .min_x = 0, .max_x = 179},
|
||||
/* y = 91 */ {.offset = 13152, .min_x = 0, .max_x = 179},
|
||||
/* y = 92 */ {.offset = 13332, .min_x = 0, .max_x = 179},
|
||||
/* y = 93 */ {.offset = 13512, .min_x = 0, .max_x = 179},
|
||||
/* y = 94 */ {.offset = 13692, .min_x = 0, .max_x = 179},
|
||||
/* y = 95 */ {.offset = 13872, .min_x = 0, .max_x = 179},
|
||||
/* y = 96 */ {.offset = 14052, .min_x = 0, .max_x = 179},
|
||||
/* y = 97 */ {.offset = 14232, .min_x = 0, .max_x = 179},
|
||||
/* y = 98 */ {.offset = 14412, .min_x = 0, .max_x = 179},
|
||||
/* y = 99 */ {.offset = 14592, .min_x = 0, .max_x = 179},
|
||||
/* y = 100 */ {.offset = 14772, .min_x = 0, .max_x = 179},
|
||||
/* y = 101 */ {.offset = 14952, .min_x = 0, .max_x = 179},
|
||||
/* y = 102 */ {.offset = 15132, .min_x = 0, .max_x = 179},
|
||||
/* y = 103 */ {.offset = 15312, .min_x = 0, .max_x = 179},
|
||||
/* y = 104 */ {.offset = 15491, .min_x = 1, .max_x = 178},
|
||||
/* y = 105 */ {.offset = 15669, .min_x = 1, .max_x = 178},
|
||||
/* y = 106 */ {.offset = 15847, .min_x = 1, .max_x = 178},
|
||||
/* y = 107 */ {.offset = 16025, .min_x = 1, .max_x = 178},
|
||||
/* y = 108 */ {.offset = 16203, .min_x = 1, .max_x = 178},
|
||||
/* y = 109 */ {.offset = 16380, .min_x = 2, .max_x = 177},
|
||||
/* y = 110 */ {.offset = 16556, .min_x = 2, .max_x = 177},
|
||||
/* y = 111 */ {.offset = 16732, .min_x = 2, .max_x = 177},
|
||||
/* y = 112 */ {.offset = 16908, .min_x = 2, .max_x = 177},
|
||||
/* y = 113 */ {.offset = 17084, .min_x = 2, .max_x = 177},
|
||||
/* y = 114 */ {.offset = 17259, .min_x = 3, .max_x = 176},
|
||||
/* y = 115 */ {.offset = 17433, .min_x = 3, .max_x = 176},
|
||||
/* y = 116 */ {.offset = 17607, .min_x = 3, .max_x = 176},
|
||||
/* y = 117 */ {.offset = 17780, .min_x = 4, .max_x = 175},
|
||||
/* y = 118 */ {.offset = 17952, .min_x = 4, .max_x = 175},
|
||||
/* y = 119 */ {.offset = 18124, .min_x = 4, .max_x = 175},
|
||||
/* y = 120 */ {.offset = 18295, .min_x = 5, .max_x = 174},
|
||||
/* y = 121 */ {.offset = 18465, .min_x = 5, .max_x = 174},
|
||||
/* y = 122 */ {.offset = 18635, .min_x = 5, .max_x = 174},
|
||||
/* y = 123 */ {.offset = 18804, .min_x = 6, .max_x = 173},
|
||||
/* y = 124 */ {.offset = 18972, .min_x = 6, .max_x = 173},
|
||||
/* y = 125 */ {.offset = 19139, .min_x = 7, .max_x = 172},
|
||||
/* y = 126 */ {.offset = 19305, .min_x = 7, .max_x = 172},
|
||||
/* y = 127 */ {.offset = 19471, .min_x = 7, .max_x = 172},
|
||||
/* y = 128 */ {.offset = 19636, .min_x = 8, .max_x = 171},
|
||||
/* y = 129 */ {.offset = 19800, .min_x = 8, .max_x = 171},
|
||||
/* y = 130 */ {.offset = 19963, .min_x = 9, .max_x = 170},
|
||||
/* y = 131 */ {.offset = 20125, .min_x = 9, .max_x = 170},
|
||||
/* y = 132 */ {.offset = 20286, .min_x = 10, .max_x = 169},
|
||||
/* y = 133 */ {.offset = 20446, .min_x = 10, .max_x = 169},
|
||||
/* y = 134 */ {.offset = 20605, .min_x = 11, .max_x = 168},
|
||||
/* y = 135 */ {.offset = 20762, .min_x = 12, .max_x = 167},
|
||||
/* y = 136 */ {.offset = 20918, .min_x = 12, .max_x = 167},
|
||||
/* y = 137 */ {.offset = 21073, .min_x = 13, .max_x = 166},
|
||||
/* y = 138 */ {.offset = 21227, .min_x = 13, .max_x = 166},
|
||||
/* y = 139 */ {.offset = 21380, .min_x = 14, .max_x = 165},
|
||||
/* y = 140 */ {.offset = 21531, .min_x = 15, .max_x = 164},
|
||||
/* y = 141 */ {.offset = 21681, .min_x = 15, .max_x = 164},
|
||||
/* y = 142 */ {.offset = 21830, .min_x = 16, .max_x = 163},
|
||||
/* y = 143 */ {.offset = 21977, .min_x = 17, .max_x = 162},
|
||||
/* y = 144 */ {.offset = 22122, .min_x = 18, .max_x = 161},
|
||||
/* y = 145 */ {.offset = 22266, .min_x = 18, .max_x = 161},
|
||||
/* y = 146 */ {.offset = 22409, .min_x = 19, .max_x = 160},
|
||||
/* y = 147 */ {.offset = 22550, .min_x = 20, .max_x = 159},
|
||||
/* y = 148 */ {.offset = 22689, .min_x = 21, .max_x = 158},
|
||||
/* y = 149 */ {.offset = 22826, .min_x = 22, .max_x = 157},
|
||||
/* y = 150 */ {.offset = 22962, .min_x = 22, .max_x = 157},
|
||||
/* y = 151 */ {.offset = 23097, .min_x = 23, .max_x = 156},
|
||||
/* y = 152 */ {.offset = 23230, .min_x = 24, .max_x = 155},
|
||||
/* y = 153 */ {.offset = 23361, .min_x = 25, .max_x = 154},
|
||||
/* y = 154 */ {.offset = 23490, .min_x = 26, .max_x = 153},
|
||||
/* y = 155 */ {.offset = 23617, .min_x = 27, .max_x = 152},
|
||||
/* y = 156 */ {.offset = 23742, .min_x = 28, .max_x = 151},
|
||||
/* y = 157 */ {.offset = 23865, .min_x = 29, .max_x = 150},
|
||||
/* y = 158 */ {.offset = 23985, .min_x = 31, .max_x = 148},
|
||||
/* y = 159 */ {.offset = 24102, .min_x = 32, .max_x = 147},
|
||||
/* y = 160 */ {.offset = 24217, .min_x = 33, .max_x = 146},
|
||||
/* y = 161 */ {.offset = 24330, .min_x = 34, .max_x = 145},
|
||||
/* y = 162 */ {.offset = 24440, .min_x = 36, .max_x = 143},
|
||||
/* y = 163 */ {.offset = 24547, .min_x = 37, .max_x = 142},
|
||||
/* y = 164 */ {.offset = 24652, .min_x = 38, .max_x = 141},
|
||||
/* y = 165 */ {.offset = 24754, .min_x = 40, .max_x = 139},
|
||||
/* y = 166 */ {.offset = 24853, .min_x = 41, .max_x = 138},
|
||||
/* y = 167 */ {.offset = 24949, .min_x = 43, .max_x = 136},
|
||||
/* y = 168 */ {.offset = 25041, .min_x = 45, .max_x = 134},
|
||||
/* y = 169 */ {.offset = 25130, .min_x = 46, .max_x = 133},
|
||||
/* y = 170 */ {.offset = 25216, .min_x = 48, .max_x = 131},
|
||||
/* y = 171 */ {.offset = 25298, .min_x = 50, .max_x = 129},
|
||||
/* y = 172 */ {.offset = 25376, .min_x = 52, .max_x = 127},
|
||||
/* y = 173 */ {.offset = 25449, .min_x = 55, .max_x = 124},
|
||||
/* y = 174 */ {.offset = 25517, .min_x = 57, .max_x = 122},
|
||||
/* y = 175 */ {.offset = 25580, .min_x = 60, .max_x = 119},
|
||||
/* y = 176 */ {.offset = 25637, .min_x = 63, .max_x = 116},
|
||||
/* y = 177 */ {.offset = 25688, .min_x = 66, .max_x = 113},
|
||||
/* y = 178 */ {.offset = 25731, .min_x = 71, .max_x = 108},
|
||||
/* y = 179 */ {.offset = 25764, .min_x = 76, .max_x = 103},
|
||||
};
|
42
src/fw/board/displays/display_spalding.h
Normal file
42
src/fw/board/displays/display_spalding.h
Normal file
|
@ -0,0 +1,42 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
#define DISPLAY_ORIENTATION_COLUMN_MAJOR_INVERTED 0
|
||||
#define DISPLAY_ORIENTATION_ROTATED_180 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR 1
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR_INVERTED 0
|
||||
|
||||
#define PBL_BW 0
|
||||
#define PBL_COLOR 1
|
||||
|
||||
#define PBL_RECT 0
|
||||
#define PBL_ROUND 1
|
||||
|
||||
#define PBL_DISPLAY_WIDTH 180
|
||||
#define PBL_DISPLAY_HEIGHT 180
|
||||
|
||||
// Spalding doesn't support 2x apps, but need to define these anyways so it builds
|
||||
#define LEGACY_2X_DISP_COLS DISP_COLS
|
||||
#define LEGACY_2X_DISP_ROWS DISP_ROWS
|
||||
#define LEGACY_3X_DISP_COLS DISP_COLS
|
||||
#define LEGACY_3X_DISP_ROWS DISP_ROWS
|
||||
|
||||
// all pixels + 76 padding pixels before the first/after the last row
|
||||
#define DISPLAY_FRAMEBUFFER_BYTES 25944
|
||||
|
||||
extern const void * const g_gbitmap_spalding_data_row_infos;
|
40
src/fw/board/displays/display_tintin.h
Normal file
40
src/fw/board/displays/display_tintin.h
Normal 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
|
||||
|
||||
#define DISPLAY_ORIENTATION_COLUMN_MAJOR_INVERTED 0
|
||||
#define DISPLAY_ORIENTATION_ROTATED_180 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR 0
|
||||
#define DISPLAY_ORIENTATION_ROW_MAJOR_INVERTED 0
|
||||
|
||||
#define PBL_BW 1
|
||||
#define PBL_COLOR 0
|
||||
|
||||
#define PBL_RECT 1
|
||||
#define PBL_ROUND 0
|
||||
|
||||
#define PBL_DISPLAY_WIDTH 144
|
||||
#define PBL_DISPLAY_HEIGHT 168
|
||||
|
||||
#define LEGACY_2X_DISP_COLS PBL_DISPLAY_WIDTH
|
||||
#define LEGACY_2X_DISP_ROWS PBL_DISPLAY_HEIGHT
|
||||
// tintin won't get 4x but set legacy3x values anyways to keep it building
|
||||
#define LEGACY_3X_DISP_COLS PBL_DISPLAY_WIDTH
|
||||
#define LEGACY_3X_DISP_ROWS PBL_DISPLAY_HEIGHT
|
||||
|
||||
#define DISPLAY_FRAMEBUFFER_BYTES \
|
||||
(ROUND_TO_MOD_CEIL(PBL_DISPLAY_WIDTH, 32) / 8 * PBL_DISPLAY_HEIGHT)
|
94
src/fw/board/wscript_build
Normal file
94
src/fw/board/wscript_build
Normal file
|
@ -0,0 +1,94 @@
|
|||
board = bld.get_board()
|
||||
if board in ('bb2',):
|
||||
bld.objects(
|
||||
name='board',
|
||||
source=[
|
||||
'boards/board_bb2.c',
|
||||
],
|
||||
use=[
|
||||
'fw_includes',
|
||||
'drivers',
|
||||
],
|
||||
)
|
||||
elif board in ('ev2_4',):
|
||||
bld.objects(
|
||||
name='board',
|
||||
source=[
|
||||
'boards/board_ev2_4.c',
|
||||
],
|
||||
use=[
|
||||
'fw_includes',
|
||||
'drivers',
|
||||
],
|
||||
)
|
||||
elif board in ('v1_5',):
|
||||
bld.objects(
|
||||
name='board',
|
||||
source=[
|
||||
'boards/board_v1_5.c',
|
||||
],
|
||||
use=[
|
||||
'fw_includes',
|
||||
'drivers',
|
||||
],
|
||||
)
|
||||
elif board in ('v2_0',):
|
||||
bld.objects(
|
||||
name='board',
|
||||
source=[
|
||||
'boards/board_v2_0.c',
|
||||
],
|
||||
use=[
|
||||
'fw_includes',
|
||||
'drivers',
|
||||
],
|
||||
)
|
||||
elif board in ('snowy_bb2','snowy_evt2','snowy_dvt','snowy_s3'):
|
||||
bld.objects(
|
||||
name='board',
|
||||
source=[
|
||||
'boards/board_snowy.c',
|
||||
],
|
||||
use=[
|
||||
'fw_includes',
|
||||
'drivers',
|
||||
],
|
||||
)
|
||||
elif board in ('spalding_evt','spalding', 'spalding_bb2'):
|
||||
bld.objects(
|
||||
name='board',
|
||||
source=[
|
||||
'boards/board_spalding_evt.c',
|
||||
],
|
||||
use=[
|
||||
'fw_includes',
|
||||
'drivers',
|
||||
],
|
||||
)
|
||||
elif board in ('silk_evt', 'silk_bb', 'silk_bb2', 'silk',):
|
||||
bld.objects(
|
||||
name='board',
|
||||
source=[
|
||||
'boards/board_silk.c',
|
||||
],
|
||||
use=[
|
||||
'fw_includes',
|
||||
'drivers',
|
||||
],
|
||||
)
|
||||
elif board in ('cutts_bb','robert_bb','robert_bb2','robert_evt'):
|
||||
bld.objects(
|
||||
name='board',
|
||||
source=[
|
||||
'boards/board_robert.c',
|
||||
],
|
||||
use=[
|
||||
'fw_includes',
|
||||
'drivers',
|
||||
],
|
||||
)
|
||||
else:
|
||||
bld.fatal('src/fw/board/wscript_build: '
|
||||
'Unknown board {}'.format(board))
|
||||
|
||||
# vim:filetype=python
|
Loading…
Add table
Add a link
Reference in a new issue