Initial InfiniSim project

This commit is contained in:
Reinhold Gschweicher
2022-02-16 21:42:29 +01:00
parent cea006b049
commit f19355949b
78 changed files with 9978 additions and 0 deletions

134
sim/drivers/Bma421.cpp Normal file
View File

@@ -0,0 +1,134 @@
#include "drivers/Bma421.h"
#include <libraries/delay/nrf_delay.h>
#include <libraries/log/nrf_log.h>
#include "drivers/TwiMaster.h"
#include <drivers/Bma421_C/bma423.h>
using namespace Pinetime::Drivers;
namespace {
// int8_t user_i2c_read(uint8_t reg_addr, uint8_t* reg_data, uint32_t length, void* intf_ptr) {
// auto bma421 = static_cast<Bma421*>(intf_ptr);
// bma421->Read(reg_addr, reg_data, length);
// return 0;
// }
//
// int8_t user_i2c_write(uint8_t reg_addr, const uint8_t* reg_data, uint32_t length, void* intf_ptr) {
// auto bma421 = static_cast<Bma421*>(intf_ptr);
// bma421->Write(reg_addr, reg_data, length);
// return 0;
// }
//
// void user_delay(uint32_t period_us, void* intf_ptr) {
// nrf_delay_us(period_us);
// }
}
Bma421::Bma421(TwiMaster& twiMaster, uint8_t twiAddress) : twiMaster {twiMaster}, deviceAddress {twiAddress} {
// bma.intf = BMA4_I2C_INTF;
// bma.bus_read = user_i2c_read;
// bma.bus_write = user_i2c_write;
// bma.variant = BMA42X_VARIANT;
// bma.intf_ptr = this;
// bma.delay_us = user_delay;
// bma.read_write_len = 16;
}
void Bma421::Init() {
if (not isResetOk)
return; // Call SoftReset (and reset TWI device) first!
// auto ret = bma423_init(&bma);
// if (ret != BMA4_OK)
// return;
switch(bma.chip_id) {
case BMA423_CHIP_ID: deviceType = DeviceTypes::BMA421; break;
case BMA425_CHIP_ID: deviceType = DeviceTypes::BMA425; break;
default: deviceType = DeviceTypes::Unknown; break;
}
// ret = bma423_write_config_file(&bma);
// if (ret != BMA4_OK)
// return;
//
// ret = bma4_set_interrupt_mode(BMA4_LATCH_MODE, &bma);
// if (ret != BMA4_OK)
// return;
//
// ret = bma423_feature_enable(BMA423_STEP_CNTR, 1, &bma);
// if (ret != BMA4_OK)
// return;
//
// ret = bma423_step_detector_enable(0, &bma);
// if (ret != BMA4_OK)
// return;
//
// ret = bma4_set_accel_enable(1, &bma);
// if (ret != BMA4_OK)
// return;
//
// struct bma4_accel_config accel_conf;
// accel_conf.odr = BMA4_OUTPUT_DATA_RATE_100HZ;
// accel_conf.range = BMA4_ACCEL_RANGE_2G;
// accel_conf.bandwidth = BMA4_ACCEL_NORMAL_AVG4;
// accel_conf.perf_mode = BMA4_CIC_AVG_MODE;
// ret = bma4_set_accel_config(&accel_conf, &bma);
// if (ret != BMA4_OK)
// return;
//
isOk = true;
}
void Bma421::Reset() {
uint8_t data = 0xb6;
twiMaster.Write(deviceAddress, 0x7E, &data, 1);
}
void Bma421::Read(uint8_t registerAddress, uint8_t* buffer, size_t size) {
twiMaster.Read(deviceAddress, registerAddress, buffer, size);
}
void Bma421::Write(uint8_t registerAddress, const uint8_t* data, size_t size) {
twiMaster.Write(deviceAddress, registerAddress, data, size);
}
Bma421::Values Bma421::Process() {
if (not isOk)
return {};
// struct bma4_accel data;
// bma4_read_accel_xyz(&data, &bma);
//
// uint32_t steps = 0;
// bma423_step_counter_output(&steps, &bma);
//
// int32_t temperature = 0;
// bma4_get_temperature(&temperature, BMA4_DEG, &bma);
// temperature = temperature / 1000;
//
// uint8_t activity = 0;
// bma423_activity_output(&activity, &bma);
//
// // X and Y axis are swapped because of the way the sensor is mounted in the PineTime
// return {steps, data.y, data.x, data.z};
return {steps, 0, 0, 0};
}
bool Bma421::IsOk() const {
return isOk;
}
void Bma421::ResetStepCounter() {
// bma423_reset_step_counter(&bma);
steps = 0;
}
void Bma421::SoftReset() {
// auto ret = bma4_soft_reset(&bma);
// if (ret == BMA4_OK) {
// isResetOk = true;
// nrf_delay_ms(1);
// }
}
Bma421::DeviceTypes Bma421::DeviceType() const {
return deviceType;
}

56
sim/drivers/Bma421.h Normal file
View File

@@ -0,0 +1,56 @@
#pragma once
#include <drivers/Bma421_C/bma4_defs.h>
#include <cstdint>
#include <cstddef>
#include <memory>
namespace Pinetime {
namespace Drivers {
class TwiMaster;
class Bma421 {
public:
enum class DeviceTypes : uint8_t {
Unknown,
BMA421,
BMA425
};
struct Values {
uint32_t steps;
int16_t x;
int16_t y;
int16_t z;
};
Bma421(TwiMaster& twiMaster, uint8_t twiAddress);
Bma421(const Bma421&) = delete;
Bma421& operator=(const Bma421&) = delete;
Bma421(Bma421&&) = delete;
Bma421& operator=(Bma421&&) = delete;
/// The chip freezes the TWI bus after the softreset operation. Softreset is separated from the
/// Init() method to allow the caller to uninit and then reinit the TWI device after the softreset.
void SoftReset();
void Init();
Values Process();
void ResetStepCounter();
void Read(uint8_t registerAddress, uint8_t* buffer, size_t size);
void Write(uint8_t registerAddress, const uint8_t* data, size_t size);
bool IsOk() const;
DeviceTypes DeviceType() const;
// lv_sim: returned by Process(), public to be modified by main.cpp
uint32_t steps = 0;
private:
void Reset();
TwiMaster& twiMaster;
uint8_t deviceAddress = 0x18;
bma4_dev bma;
bool isOk = true;
bool isResetOk = false;
DeviceTypes deviceType = DeviceTypes::Unknown;
};
}
}

112
sim/drivers/Cst816s.cpp Normal file
View File

@@ -0,0 +1,112 @@
#include "drivers/Cst816s.h"
#include <SDL2/SDL.h>
#include <libraries/log/nrf_log.h>
#include <cmath>
using namespace Pinetime::Drivers;
/* References :
* This implementation is based on this article :
* https://medium.com/@ly.lee/building-a-rust-driver-for-pinetimes-touch-controller-cbc1a5d5d3e9 Touch panel datasheet (weird chinese
* translation) : https://wiki.pine64.org/images/5/51/CST816S%E6%95%B0%E6%8D%AE%E6%89%8B%E5%86%8CV1.1.en.pdf
*
* TODO : we need a complete datasheet and protocol reference!
* */
//Cst816S::Cst816S(TwiMaster& twiMaster, uint8_t twiAddress) : twiMaster {twiMaster}, twiAddress {twiAddress} {
//}
Cst816S::Cst816S() {
}
bool Cst816S::Init() {
return true;
}
Cst816S::TouchInfos Cst816S::GetTouchInfo() {
int x, y;
uint32_t buttons = SDL_GetMouseState(&x, &y);
Cst816S::TouchInfos info;
info.x = x;
info.y = y;
info.touching = (buttons & SDL_BUTTON_LMASK) != 0;
//info.gesture = gesture;
info.isValid = x > 0 && x <= maxX && y > 0 && y <= maxY;
if(info.isValid) {
if(!is_pressed && info.touching) {
// start klick
pressed_since = std::chrono::steady_clock::now();
is_pressed = true;
is_long_press = false;
is_swipe = false;
is_stationary = true;
x_start = info.x;
y_start = info.y;
} else if(is_pressed && info.touching) {
// is it long press?
if (is_stationary) { // check if while touching we moved away from the start coordinates
double x_diff = static_cast<double>(info.x) - x_start;
double y_diff = static_cast<double>(info.y) - y_start;
double norm = hypot(x_diff, y_diff);
if(norm > 20) { // we moved out of start area
is_stationary = false;
}
}
if (!is_long_press && !is_swipe) { // check for long-press only if it's not yet a long-press and didn't move
std::chrono::duration<double> press_duration = std::chrono::steady_clock::now() - pressed_since;
if(is_stationary && press_duration.count() > 1.0) {
// longer than 1 second pressed, then it is long-press
is_long_press = true;
info.gesture = Gestures::LongPress;
} else if(!is_stationary) {
// moved mouse fast enough to not be a long-press
is_swipe = true;
double x_diff = static_cast<double>(info.x) - x_start;
double y_diff = static_cast<double>(info.y) - y_start;
if (fabs(x_diff) > fabs(y_diff)) {
// x-swipe
if (x_diff < 0) {
info.gesture = Gestures::SlideLeft;
} else {
info.gesture = Gestures::SlideRight;
}
} else {
// y-swipe
if (y_diff < 0) {
info.gesture = Gestures::SlideUp;
} else {
info.gesture = Gestures::SlideDown;
}
}
}
}
} else if(is_pressed && !info.touching) {
// end klick
is_pressed = false;
double x_diff = static_cast<double>(info.x) - x_start;
double y_diff = static_cast<double>(info.y) - y_start;
double norm = hypot(x_diff, y_diff);
if(norm < 20) {
if(is_stationary && !is_long_press && !is_swipe) {
// no swipe with less than 5 pixel mouse movement
info.gesture = Gestures::SingleTap;
}
}
}
}
return info;
}
void Cst816S::Sleep() {
NRF_LOG_INFO("[TOUCHPANEL] Sleep");
}
void Cst816S::Wakeup() {
Init();
NRF_LOG_INFO("[TOUCHPANEL] Wakeup");
}
bool Cst816S::CheckDeviceIds() {
return chipId == 0xb4 && vendorId == 0 && fwVersion == 1;
}

88
sim/drivers/Cst816s.h Normal file
View File

@@ -0,0 +1,88 @@
#pragma once
//#include "drivers/TwiMaster.h"
#include <chrono>
#include <cstdint>
namespace Pinetime {
namespace Drivers {
class Cst816S {
public:
enum class Gestures : uint8_t {
None = 0x00,
SlideDown = 0x01,
SlideUp = 0x02,
SlideLeft = 0x03,
SlideRight = 0x04,
SingleTap = 0x05,
DoubleTap = 0x0B,
LongPress = 0x0C
};
struct TouchInfos {
uint16_t x = 0;
uint16_t y = 0;
Gestures gesture = Gestures::None;
bool touching = false;
bool isValid = false;
};
Cst816S();
// Cst816S(TwiMaster& twiMaster, uint8_t twiAddress);
Cst816S(const Cst816S&) = delete;
Cst816S& operator=(const Cst816S&) = delete;
Cst816S(Cst816S&&) = delete;
Cst816S& operator=(Cst816S&&) = delete;
bool Init();
TouchInfos GetTouchInfo();
void Sleep();
void Wakeup();
uint8_t GetChipId() const {
return chipId;
}
uint8_t GetVendorId() const {
return vendorId;
}
uint8_t GetFwVersion() const {
return fwVersion;
}
private:
bool CheckDeviceIds();
// Unused/Unavailable commented out
static constexpr uint8_t gestureIndex = 1;
static constexpr uint8_t touchPointNumIndex = 2;
//static constexpr uint8_t touchEventIndex = 3;
static constexpr uint8_t touchXHighIndex = 3;
static constexpr uint8_t touchXLowIndex = 4;
//static constexpr uint8_t touchIdIndex = 5;
static constexpr uint8_t touchYHighIndex = 5;
static constexpr uint8_t touchYLowIndex = 6;
//static constexpr uint8_t touchStep = 6;
//static constexpr uint8_t touchXYIndex = 7;
//static constexpr uint8_t touchMiscIndex = 8;
static constexpr uint8_t maxX = 240;
static constexpr uint8_t maxY = 240;
// TwiMaster& twiMaster;
// uint8_t twiAddress;
const uint8_t chipId = 0xb4;
const uint8_t vendorId = 0;
const uint8_t fwVersion = 1;
// simulation members for swipe detection from mouse
std::chrono::time_point<std::chrono::steady_clock> pressed_since;
bool is_pressed = false;
bool is_long_press = false;
bool is_stationary = true;
bool is_swipe = false;
uint8_t x_start;
uint8_t y_start;
};
}
}

105
sim/drivers/Hrs3300.cpp Normal file
View File

@@ -0,0 +1,105 @@
/*
SPDX-License-Identifier: LGPL-3.0-or-later
Original work Copyright (C) 2020 Daniel Thompson
C++ port Copyright (C) 2021 Jean-François Milants
*/
#include "drivers/Hrs3300.h"
#include <algorithm>
#include <nrf_gpio.h>
#include <FreeRTOS.h>
#include <task.h>
#include <nrf_log.h>
using namespace Pinetime::Drivers;
/** Driver for the HRS3300 heart rate sensor.
* Original implementation from wasp-os : https://github.com/daniel-thompson/wasp-os/blob/master/wasp/drivers/hrs3300.py
*/
Hrs3300::Hrs3300(TwiMaster& twiMaster, uint8_t twiAddress) : twiMaster {twiMaster}, twiAddress {twiAddress} {
}
void Hrs3300::Init() {
nrf_gpio_cfg_input(30, NRF_GPIO_PIN_NOPULL);
Disable();
// vTaskDelay(100);
// HRS disabled, 12.5 ms wait time between cycles, (partly) 20mA drive
WriteRegister(static_cast<uint8_t>(Registers::Enable), 0x60);
// (partly) 20mA drive, power on, "magic" (datasheet says both
// "reserved" and "set low nibble to 8" but 0xe gives better results
// and is used by at least two other HRS3300 drivers
WriteRegister(static_cast<uint8_t>(Registers::PDriver), 0x6E);
// HRS and ALS both in 16-bit mode
WriteRegister(static_cast<uint8_t>(Registers::Res), 0x88);
// 64x gain
WriteRegister(static_cast<uint8_t>(Registers::Hgain), 0x10);
}
void Hrs3300::Enable() {
NRF_LOG_INFO("ENABLE");
auto value = ReadRegister(static_cast<uint8_t>(Registers::Enable));
value |= 0x80;
WriteRegister(static_cast<uint8_t>(Registers::Enable), value);
}
void Hrs3300::Disable() {
NRF_LOG_INFO("DISABLE");
auto value = ReadRegister(static_cast<uint8_t>(Registers::Enable));
value &= ~0x80;
WriteRegister(static_cast<uint8_t>(Registers::Enable), value);
}
uint16_t Hrs3300::ReadHrs() {
auto m = ReadRegister(static_cast<uint8_t>(Registers::C0DataM));
auto h = ReadRegister(static_cast<uint8_t>(Registers::C0DataH));
auto l = ReadRegister(static_cast<uint8_t>(Registers::C0dataL));
return (m << 8) | ((h & 0x0f) << 4) | (l & 0x0f) | ((l & 0x30) << 12);
}
uint16_t Hrs3300::ReadAls() {
auto m = ReadRegister(static_cast<uint8_t>(Registers::C1dataM));
auto h = ReadRegister(static_cast<uint8_t>(Registers::C1dataH));
auto l = ReadRegister(static_cast<uint8_t>(Registers::C1dataL));
return (m << 3) | ((h & 0x3f) << 11) | (l & 0x07);
}
void Hrs3300::SetGain(uint8_t gain) {
constexpr uint8_t maxGain = 64U;
gain = std::min(gain, maxGain);
uint8_t hgain = 0;
while ((1 << hgain) < gain) {
++hgain;
}
WriteRegister(static_cast<uint8_t>(Registers::Hgain), hgain << 2);
}
void Hrs3300::SetDrive(uint8_t drive) {
auto en = ReadRegister(static_cast<uint8_t>(Registers::Enable));
auto pd = ReadRegister(static_cast<uint8_t>(Registers::PDriver));
en = (en & 0xf7) | ((drive & 2) << 2);
pd = (pd & 0xbf) | ((drive & 1) << 6);
WriteRegister(static_cast<uint8_t>(Registers::Enable), en);
WriteRegister(static_cast<uint8_t>(Registers::PDriver), pd);
}
void Hrs3300::WriteRegister(uint8_t reg, uint8_t data) {
auto ret = twiMaster.Write(twiAddress, reg, &data, 1);
if (ret != TwiMaster::ErrorCodes::NoError)
NRF_LOG_INFO("WRITE ERROR");
}
uint8_t Hrs3300::ReadRegister(uint8_t reg) {
uint8_t value;
auto ret = twiMaster.Read(twiAddress, reg, &value, 1);
if (ret != TwiMaster::ErrorCodes::NoError)
NRF_LOG_INFO("READ ERROR");
return value;
}

46
sim/drivers/Hrs3300.h Normal file
View File

@@ -0,0 +1,46 @@
#pragma once
#include "drivers/TwiMaster.h"
namespace Pinetime {
namespace Drivers {
class Hrs3300 {
public:
enum class Registers : uint8_t {
Id = 0x00,
Enable = 0x01,
EnableHen = 0x80,
C1dataM = 0x08,
C0DataM = 0x09,
C0DataH = 0x0a,
PDriver = 0x0c,
C1dataH = 0x0d,
C1dataL = 0x0e,
C0dataL = 0x0f,
Res = 0x16,
Hgain = 0x17
};
Hrs3300(TwiMaster& twiMaster, uint8_t twiAddress);
Hrs3300(const Hrs3300&) = delete;
Hrs3300& operator=(const Hrs3300&) = delete;
Hrs3300(Hrs3300&&) = delete;
Hrs3300& operator=(Hrs3300&&) = delete;
void Init();
void Enable();
void Disable();
uint16_t ReadHrs();
uint16_t ReadAls();
void SetGain(uint8_t gain);
void SetDrive(uint8_t drive);
private:
TwiMaster& twiMaster;
uint8_t twiAddress;
void WriteRegister(uint8_t reg, uint8_t data);
uint8_t ReadRegister(uint8_t reg);
};
}
}

296
sim/drivers/SpiMaster.cpp Normal file
View File

@@ -0,0 +1,296 @@
#include "drivers/SpiMaster.h"
//#include <hal/nrf_gpio.h>
//#include <hal/nrf_spim.h>
#include <nrfx_log.h>
#include <algorithm>
using namespace Pinetime::Drivers;
SpiMaster::SpiMaster(const SpiMaster::SpiModule spi, const SpiMaster::Parameters& params) : spi {spi}, params {params} {
}
bool SpiMaster::Init() {
// if(mutex == nullptr) {
// mutex = xSemaphoreCreateBinary();
// ASSERT(mutex != nullptr);
// }
//
// /* Configure GPIO pins used for pselsck, pselmosi, pselmiso and pselss for SPI0 */
// nrf_gpio_pin_set(params.pinSCK);
// nrf_gpio_cfg_output(params.pinSCK);
// nrf_gpio_pin_clear(params.pinMOSI);
// nrf_gpio_cfg_output(params.pinMOSI);
// nrf_gpio_cfg_input(params.pinMISO, NRF_GPIO_PIN_NOPULL);
// // nrf_gpio_cfg_output(params.pinCSN);
// // pinCsn = params.pinCSN;
//
// switch (spi) {
// case SpiModule::SPI0:
// spiBaseAddress = NRF_SPIM0;
// break;
// case SpiModule::SPI1:
// spiBaseAddress = NRF_SPIM1;
// break;
// default:
// return false;
// }
//
// /* Configure pins, frequency and mode */
// spiBaseAddress->PSELSCK = params.pinSCK;
// spiBaseAddress->PSELMOSI = params.pinMOSI;
// spiBaseAddress->PSELMISO = params.pinMISO;
//
// uint32_t frequency;
// switch (params.Frequency) {
// case Frequencies::Freq8Mhz:
// frequency = 0x80000000;
// break;
// default:
// return false;
// }
// spiBaseAddress->FREQUENCY = frequency;
//
// uint32_t regConfig = 0;
// switch (params.bitOrder) {
// case BitOrder::Msb_Lsb:
// break;
// case BitOrder::Lsb_Msb:
// regConfig = 1;
// break;
// default:
// return false;
// }
// switch (params.mode) {
// case Modes::Mode0:
// break;
// case Modes::Mode1:
// regConfig |= (0x01 << 1);
// break;
// case Modes::Mode2:
// regConfig |= (0x02 << 1);
// break;
// case Modes::Mode3:
// regConfig |= (0x03 << 1);
// break;
// default:
// return false;
// }
//
// spiBaseAddress->CONFIG = regConfig;
// spiBaseAddress->EVENTS_ENDRX = 0;
// spiBaseAddress->EVENTS_ENDTX = 0;
// spiBaseAddress->EVENTS_END = 0;
//
// spiBaseAddress->INTENSET = ((unsigned) 1 << (unsigned) 6);
// spiBaseAddress->INTENSET = ((unsigned) 1 << (unsigned) 1);
// spiBaseAddress->INTENSET = ((unsigned) 1 << (unsigned) 19);
//
// spiBaseAddress->ENABLE = (SPIM_ENABLE_ENABLE_Enabled << SPIM_ENABLE_ENABLE_Pos);
//
// NRFX_IRQ_PRIORITY_SET(SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQn, 2);
// NRFX_IRQ_ENABLE(SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQn);
//
// xSemaphoreGive(mutex);
return true;
}
//void SpiMaster::SetupWorkaroundForFtpan58(NRF_SPIM_Type* spim, uint32_t ppi_channel, uint32_t gpiote_channel) {
// // Create an event when SCK toggles.
// NRF_GPIOTE->CONFIG[gpiote_channel] = (GPIOTE_CONFIG_MODE_Event << GPIOTE_CONFIG_MODE_Pos) | (spim->PSEL.SCK << GPIOTE_CONFIG_PSEL_Pos) |
// (GPIOTE_CONFIG_POLARITY_Toggle << GPIOTE_CONFIG_POLARITY_Pos);
//
// // Stop the spim instance when SCK toggles.
// NRF_PPI->CH[ppi_channel].EEP = (uint32_t) &NRF_GPIOTE->EVENTS_IN[gpiote_channel];
// NRF_PPI->CH[ppi_channel].TEP = (uint32_t) &spim->TASKS_STOP;
// NRF_PPI->CHENSET = 1U << ppi_channel;
// spiBaseAddress->EVENTS_END = 0;
//
// // Disable IRQ
// spim->INTENCLR = (1 << 6);
// spim->INTENCLR = (1 << 1);
// spim->INTENCLR = (1 << 19);
//}
//void SpiMaster::DisableWorkaroundForFtpan58(NRF_SPIM_Type* spim, uint32_t ppi_channel, uint32_t gpiote_channel) {
// NRF_GPIOTE->CONFIG[gpiote_channel] = 0;
// NRF_PPI->CH[ppi_channel].EEP = 0;
// NRF_PPI->CH[ppi_channel].TEP = 0;
// NRF_PPI->CHENSET = ppi_channel;
// spiBaseAddress->EVENTS_END = 0;
// spim->INTENSET = (1 << 6);
// spim->INTENSET = (1 << 1);
// spim->INTENSET = (1 << 19);
//}
void SpiMaster::OnEndEvent() {
if (currentBufferAddr == 0) {
return;
}
// auto s = currentBufferSize;
// if (s > 0) {
// auto currentSize = std::min((size_t) 255, s);
// PrepareTx(currentBufferAddr, currentSize);
// currentBufferAddr += currentSize;
// currentBufferSize -= currentSize;
//
// spiBaseAddress->TASKS_START = 1;
// } else {
// BaseType_t xHigherPriorityTaskWoken = pdFALSE;
// if (taskToNotify != nullptr) {
// vTaskNotifyGiveFromISR(taskToNotify, &xHigherPriorityTaskWoken);
// portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
// }
//
// nrf_gpio_pin_set(this->pinCsn);
// currentBufferAddr = 0;
// BaseType_t xHigherPriorityTaskWoken2 = pdFALSE;
// xSemaphoreGiveFromISR(mutex, &xHigherPriorityTaskWoken2);
// portYIELD_FROM_ISR(xHigherPriorityTaskWoken | xHigherPriorityTaskWoken2);
// }
}
void SpiMaster::OnStartedEvent() {
}
//void SpiMaster::PrepareTx(const volatile uint32_t bufferAddress, const volatile size_t size) {
// spiBaseAddress->TXD.PTR = bufferAddress;
// spiBaseAddress->TXD.MAXCNT = size;
// spiBaseAddress->TXD.LIST = 0;
// spiBaseAddress->RXD.PTR = 0;
// spiBaseAddress->RXD.MAXCNT = 0;
// spiBaseAddress->RXD.LIST = 0;
// spiBaseAddress->EVENTS_END = 0;
//}
//void SpiMaster::PrepareRx(const volatile uint32_t cmdAddress,
// const volatile size_t cmdSize,
// const volatile uint32_t bufferAddress,
// const volatile size_t size) {
// spiBaseAddress->TXD.PTR = 0;
// spiBaseAddress->TXD.MAXCNT = 0;
// spiBaseAddress->TXD.LIST = 0;
// spiBaseAddress->RXD.PTR = bufferAddress;
// spiBaseAddress->RXD.MAXCNT = size;
// spiBaseAddress->RXD.LIST = 0;
// spiBaseAddress->EVENTS_END = 0;
//}
bool SpiMaster::Write(uint8_t pinCsn, const uint8_t* data, size_t size) {
// if (data == nullptr)
// return false;
// auto ok = xSemaphoreTake(mutex, portMAX_DELAY);
// ASSERT(ok == true);
// taskToNotify = xTaskGetCurrentTaskHandle();
//
// this->pinCsn = pinCsn;
//
// if (size == 1) {
// SetupWorkaroundForFtpan58(spiBaseAddress, 0, 0);
// } else {
// DisableWorkaroundForFtpan58(spiBaseAddress, 0, 0);
// }
//
// nrf_gpio_pin_clear(this->pinCsn);
//
// currentBufferAddr = (uint32_t) data;
// currentBufferSize = size;
//
// auto currentSize = std::min((size_t) 255, (size_t) currentBufferSize);
// PrepareTx(currentBufferAddr, currentSize);
// currentBufferSize -= currentSize;
// currentBufferAddr += currentSize;
// spiBaseAddress->TASKS_START = 1;
//
// if (size == 1) {
// while (spiBaseAddress->EVENTS_END == 0)
// ;
// nrf_gpio_pin_set(this->pinCsn);
// currentBufferAddr = 0;
// xSemaphoreGive(mutex);
// }
return true;
}
bool SpiMaster::Read(uint8_t pinCsn, uint8_t* cmd, size_t cmdSize, uint8_t* data, size_t dataSize) {
// xSemaphoreTake(mutex, portMAX_DELAY);
//
// taskToNotify = nullptr;
//
// this->pinCsn = pinCsn;
// DisableWorkaroundForFtpan58(spiBaseAddress, 0, 0);
// spiBaseAddress->INTENCLR = (1 << 6);
// spiBaseAddress->INTENCLR = (1 << 1);
// spiBaseAddress->INTENCLR = (1 << 19);
//
// nrf_gpio_pin_clear(this->pinCsn);
//
// currentBufferAddr = 0;
// currentBufferSize = 0;
//
// PrepareTx((uint32_t) cmd, cmdSize);
// spiBaseAddress->TASKS_START = 1;
// while (spiBaseAddress->EVENTS_END == 0)
// ;
//
// PrepareRx((uint32_t) cmd, cmdSize, (uint32_t) data, dataSize);
// spiBaseAddress->TASKS_START = 1;
//
// while (spiBaseAddress->EVENTS_END == 0)
// ;
// nrf_gpio_pin_set(this->pinCsn);
//
// xSemaphoreGive(mutex);
return true;
}
void SpiMaster::Sleep() {
// while (spiBaseAddress->ENABLE != 0) {
// spiBaseAddress->ENABLE = (SPIM_ENABLE_ENABLE_Disabled << SPIM_ENABLE_ENABLE_Pos);
// }
// nrf_gpio_cfg_default(params.pinSCK);
// nrf_gpio_cfg_default(params.pinMOSI);
// nrf_gpio_cfg_default(params.pinMISO);
NRF_LOG_INFO("[SPIMASTER] sleep");
}
void SpiMaster::Wakeup() {
Init();
NRF_LOG_INFO("[SPIMASTER] Wakeup");
}
bool SpiMaster::WriteCmdAndBuffer(uint8_t pinCsn, const uint8_t* cmd, size_t cmdSize, const uint8_t* data, size_t dataSize) {
// xSemaphoreTake(mutex, portMAX_DELAY);
//
// taskToNotify = nullptr;
//
// this->pinCsn = pinCsn;
// DisableWorkaroundForFtpan58(spiBaseAddress, 0, 0);
// spiBaseAddress->INTENCLR = (1 << 6);
// spiBaseAddress->INTENCLR = (1 << 1);
// spiBaseAddress->INTENCLR = (1 << 19);
//
// nrf_gpio_pin_clear(this->pinCsn);
//
// currentBufferAddr = 0;
// currentBufferSize = 0;
//
// PrepareTx((uint32_t) cmd, cmdSize);
// spiBaseAddress->TASKS_START = 1;
// while (spiBaseAddress->EVENTS_END == 0)
// ;
//
// PrepareTx((uint32_t) data, dataSize);
// spiBaseAddress->TASKS_START = 1;
//
// while (spiBaseAddress->EVENTS_END == 0)
// ;
// nrf_gpio_pin_set(this->pinCsn);
//
// xSemaphoreGive(mutex);
return true;
}

65
sim/drivers/SpiMaster.h Normal file
View File

@@ -0,0 +1,65 @@
#pragma once
#include <cstddef>
#include <cstdint>
#include <FreeRTOS.h>
//#include <semphr.h>
//#include <task.h>
namespace Pinetime {
namespace Drivers {
class SpiMaster {
public:
enum class SpiModule : uint8_t { SPI0, SPI1 };
enum class BitOrder : uint8_t { Msb_Lsb, Lsb_Msb };
enum class Modes : uint8_t { Mode0, Mode1, Mode2, Mode3 };
enum class Frequencies : uint8_t { Freq8Mhz };
struct Parameters {
BitOrder bitOrder;
Modes mode;
Frequencies Frequency;
uint8_t pinSCK;
uint8_t pinMOSI;
uint8_t pinMISO;
};
SpiMaster(const SpiModule spi, const Parameters& params);
SpiMaster(const SpiMaster&) = delete;
SpiMaster& operator=(const SpiMaster&) = delete;
SpiMaster(SpiMaster&&) = delete;
SpiMaster& operator=(SpiMaster&&) = delete;
bool Init();
bool Write(uint8_t pinCsn, const uint8_t* data, size_t size);
bool Read(uint8_t pinCsn, uint8_t* cmd, size_t cmdSize, uint8_t* data, size_t dataSize);
bool WriteCmdAndBuffer(uint8_t pinCsn, const uint8_t* cmd, size_t cmdSize, const uint8_t* data, size_t dataSize);
void OnStartedEvent();
void OnEndEvent();
void Sleep();
void Wakeup();
private:
// void SetupWorkaroundForFtpan58(NRF_SPIM_Type* spim, uint32_t ppi_channel, uint32_t gpiote_channel);
// void DisableWorkaroundForFtpan58(NRF_SPIM_Type* spim, uint32_t ppi_channel, uint32_t gpiote_channel);
// void PrepareTx(const volatile uint32_t bufferAddress, const volatile size_t size);
// void PrepareRx(const volatile uint32_t cmdAddress,
// const volatile size_t cmdSize,
// const volatile uint32_t bufferAddress,
// const volatile size_t size);
// NRF_SPIM_Type* spiBaseAddress;
uint8_t pinCsn;
SpiMaster::SpiModule spi;
SpiMaster::Parameters params;
volatile uint32_t currentBufferAddr = 0;
volatile size_t currentBufferSize = 0;
// volatile TaskHandle_t taskToNotify;
// SemaphoreHandle_t mutex = nullptr;
};
}
}

144
sim/drivers/SpiNorFlash.cpp Normal file
View File

@@ -0,0 +1,144 @@
#include "drivers/SpiNorFlash.h"
#include <hal/nrf_gpio.h>
#include <libraries/delay/nrf_delay.h>
#include <libraries/log/nrf_log.h>
#include "drivers/Spi.h"
using namespace Pinetime::Drivers;
SpiNorFlash::SpiNorFlash(Spi& spi) : spi {spi} {
}
void SpiNorFlash::Init() {
device_id = ReadIdentificaion();
NRF_LOG_INFO(
"[SpiNorFlash] Manufacturer : %d, Memory type : %d, memory density : %d", device_id.manufacturer, device_id.type, device_id.density);
}
void SpiNorFlash::Uninit() {
}
void SpiNorFlash::Sleep() {
auto cmd = static_cast<uint8_t>(Commands::DeepPowerDown);
spi.Write(&cmd, sizeof(uint8_t));
NRF_LOG_INFO("[SpiNorFlash] Sleep")
}
void SpiNorFlash::Wakeup() {
// send Commands::ReleaseFromDeepPowerDown then 3 dummy bytes before reading Device ID
// static constexpr uint8_t cmdSize = 4;
// uint8_t cmd[cmdSize] = {static_cast<uint8_t>(Commands::ReleaseFromDeepPowerDown), 0x01, 0x02, 0x03};
// uint8_t id = 0;
// spi.Read(reinterpret_cast<uint8_t*>(&cmd), cmdSize, &id, 1);
// auto devId = device_id = ReadIdentificaion();
// if (devId.type != device_id.type) {
// NRF_LOG_INFO("[SpiNorFlash] ID on Wakeup: Failed");
// } else {
// NRF_LOG_INFO("[SpiNorFlash] ID on Wakeup: %d", id);
// }
NRF_LOG_INFO("[SpiNorFlash] Wakeup")
}
SpiNorFlash::Identification SpiNorFlash::ReadIdentificaion() {
// auto cmd = static_cast<uint8_t>(Commands::ReadIdentification);
// Identification identification;
// spi.Read(&cmd, 1, reinterpret_cast<uint8_t*>(&identification), sizeof(Identification));
// return identification;
return {};
}
uint8_t SpiNorFlash::ReadStatusRegister() {
auto cmd = static_cast<uint8_t>(Commands::ReadStatusRegister);
uint8_t status;
spi.Read(&cmd, sizeof(cmd), &status, sizeof(uint8_t));
return status;
}
bool SpiNorFlash::WriteInProgress() {
// return (ReadStatusRegister() & 0x01u) == 0x01u;
return false;
}
bool SpiNorFlash::WriteEnabled() {
// return (ReadStatusRegister() & 0x02u) == 0x02u;
return false;
}
uint8_t SpiNorFlash::ReadConfigurationRegister() {
auto cmd = static_cast<uint8_t>(Commands::ReadConfigurationRegister);
uint8_t status;
spi.Read(&cmd, sizeof(cmd), &status, sizeof(uint8_t));
return status;
}
void SpiNorFlash::Read(uint32_t address, uint8_t* buffer, size_t size) {
static constexpr uint8_t cmdSize = 4;
uint8_t cmd[cmdSize] = {static_cast<uint8_t>(Commands::Read), (uint8_t) (address >> 16U), (uint8_t) (address >> 8U), (uint8_t) address};
spi.Read(reinterpret_cast<uint8_t*>(&cmd), cmdSize, buffer, size);
}
void SpiNorFlash::WriteEnable() {
auto cmd = static_cast<uint8_t>(Commands::WriteEnable);
spi.Read(&cmd, sizeof(cmd), nullptr, 0);
}
void SpiNorFlash::SectorErase(uint32_t sectorAddress) {
// static constexpr uint8_t cmdSize = 4;
// uint8_t cmd[cmdSize] = {static_cast<uint8_t>(Commands::SectorErase),
// (uint8_t) (sectorAddress >> 16U),
// (uint8_t) (sectorAddress >> 8U),
// (uint8_t) sectorAddress};
//
// WriteEnable();
// while (!WriteEnabled())
// vTaskDelay(1);
//
// spi.Read(reinterpret_cast<uint8_t*>(&cmd), cmdSize, nullptr, 0);
//
// while (WriteInProgress())
// vTaskDelay(1);
}
uint8_t SpiNorFlash::ReadSecurityRegister() {
auto cmd = static_cast<uint8_t>(Commands::ReadSecurityRegister);
uint8_t status;
spi.Read(&cmd, sizeof(cmd), &status, sizeof(uint8_t));
return status;
}
bool SpiNorFlash::ProgramFailed() {
// return (ReadSecurityRegister() & 0x20u) == 0x20u;
return false;
}
bool SpiNorFlash::EraseFailed() {
// return (ReadSecurityRegister() & 0x40u) == 0x40u;
return false;
}
void SpiNorFlash::Write(uint32_t address, const uint8_t* buffer, size_t size) {
// static constexpr uint8_t cmdSize = 4;
//
// size_t len = size;
// uint32_t addr = address;
// const uint8_t* b = buffer;
// while (len > 0) {
// uint32_t pageLimit = (addr & ~(pageSize - 1u)) + pageSize;
// uint32_t toWrite = pageLimit - addr > len ? len : pageLimit - addr;
//
// uint8_t cmd[cmdSize] = {static_cast<uint8_t>(Commands::PageProgram), (uint8_t) (addr >> 16U), (uint8_t) (addr >> 8U), (uint8_t) addr};
//
// WriteEnable();
// while (!WriteEnabled())
// vTaskDelay(1);
//
// spi.WriteCmdAndBuffer(cmd, cmdSize, b, toWrite);
//
// while (WriteInProgress())
// vTaskDelay(1);
//
// addr += toWrite;
// b += toWrite;
// len -= toWrite;
// }
}

60
sim/drivers/SpiNorFlash.h Normal file
View File

@@ -0,0 +1,60 @@
#pragma once
#include <cstddef>
#include <cstdint>
namespace Pinetime {
namespace Drivers {
class Spi;
class SpiNorFlash {
public:
explicit SpiNorFlash(Spi& spi);
SpiNorFlash(const SpiNorFlash&) = delete;
SpiNorFlash& operator=(const SpiNorFlash&) = delete;
SpiNorFlash(SpiNorFlash&&) = delete;
SpiNorFlash& operator=(SpiNorFlash&&) = delete;
typedef struct __attribute__((packed)) {
uint8_t manufacturer = 0;
uint8_t type = 0;
uint8_t density = 0;
} Identification;
Identification ReadIdentificaion();
uint8_t ReadStatusRegister();
bool WriteInProgress();
bool WriteEnabled();
uint8_t ReadConfigurationRegister();
void Read(uint32_t address, uint8_t* buffer, size_t size);
void Write(uint32_t address, const uint8_t* buffer, size_t size);
void WriteEnable();
void SectorErase(uint32_t sectorAddress);
uint8_t ReadSecurityRegister();
bool ProgramFailed();
bool EraseFailed();
void Init();
void Uninit();
void Sleep();
void Wakeup();
private:
enum class Commands : uint8_t {
PageProgram = 0x02,
Read = 0x03,
ReadStatusRegister = 0x05,
WriteEnable = 0x06,
ReadConfigurationRegister = 0x15,
SectorErase = 0x20,
ReadSecurityRegister = 0x2B,
ReadIdentification = 0x9F,
ReleaseFromDeepPowerDown = 0xAB,
DeepPowerDown = 0xB9
};
static constexpr uint16_t pageSize = 256;
Spi& spi;
Identification device_id;
};
}
}

187
sim/drivers/TwiMaster.cpp Normal file
View File

@@ -0,0 +1,187 @@
#include "drivers/TwiMaster.h"
#include <cstring>
#include <hal/nrf_gpio.h>
#include <nrfx_log.h>
using namespace Pinetime::Drivers;
// TODO use shortcut to automatically send STOP when receive LastTX, for example
// TODO use DMA/IRQ
TwiMaster::TwiMaster(NRF_TWIM_Type* module, uint32_t frequency, uint8_t pinSda, uint8_t pinScl)
: module {module}, frequency {frequency}, pinSda {pinSda}, pinScl {pinScl} {
}
//void TwiMaster::ConfigurePins() const {
// NRF_GPIO->PIN_CNF[pinScl] =
// (GPIO_PIN_CNF_DIR_Input << GPIO_PIN_CNF_DIR_Pos) |
// (GPIO_PIN_CNF_INPUT_Connect << GPIO_PIN_CNF_INPUT_Pos) |
// (GPIO_PIN_CNF_PULL_Disabled << GPIO_PIN_CNF_PULL_Pos) |
// (GPIO_PIN_CNF_DRIVE_S0D1 << GPIO_PIN_CNF_DRIVE_Pos) |
// (GPIO_PIN_CNF_SENSE_Disabled << GPIO_PIN_CNF_SENSE_Pos);
//
// NRF_GPIO->PIN_CNF[pinSda] =
// (GPIO_PIN_CNF_DIR_Input << GPIO_PIN_CNF_DIR_Pos) |
// (GPIO_PIN_CNF_INPUT_Connect << GPIO_PIN_CNF_INPUT_Pos) |
// (GPIO_PIN_CNF_PULL_Disabled << GPIO_PIN_CNF_PULL_Pos) |
// (GPIO_PIN_CNF_DRIVE_S0D1 << GPIO_PIN_CNF_DRIVE_Pos) |
// (GPIO_PIN_CNF_SENSE_Disabled << GPIO_PIN_CNF_SENSE_Pos);
//}
void TwiMaster::Init() {
// if (mutex == nullptr) {
// mutex = xSemaphoreCreateBinary();
// }
//
// ConfigurePins();
//
// twiBaseAddress = module;
//
// twiBaseAddress->FREQUENCY = frequency;
//
// twiBaseAddress->PSEL.SCL = pinScl;
// twiBaseAddress->PSEL.SDA = pinSda;
// twiBaseAddress->EVENTS_LASTRX = 0;
// twiBaseAddress->EVENTS_STOPPED = 0;
// twiBaseAddress->EVENTS_LASTTX = 0;
// twiBaseAddress->EVENTS_ERROR = 0;
// twiBaseAddress->EVENTS_RXSTARTED = 0;
// twiBaseAddress->EVENTS_SUSPENDED = 0;
// twiBaseAddress->EVENTS_TXSTARTED = 0;
//
// twiBaseAddress->ENABLE = (TWIM_ENABLE_ENABLE_Enabled << TWIM_ENABLE_ENABLE_Pos);
//
// xSemaphoreGive(mutex);
}
TwiMaster::ErrorCodes TwiMaster::Read(uint8_t deviceAddress, uint8_t registerAddress, uint8_t* data, size_t size) {
// xSemaphoreTake(mutex, portMAX_DELAY);
// Wakeup();
// auto ret = Write(deviceAddress, &registerAddress, 1, false);
// ret = Read(deviceAddress, data, size, true);
// Sleep();
// xSemaphoreGive(mutex);
// return ret;
return TwiMaster::ErrorCodes::NoError;
}
TwiMaster::ErrorCodes TwiMaster::Write(uint8_t deviceAddress, uint8_t registerAddress, const uint8_t* data, size_t size) {
// ASSERT(size <= maxDataSize);
// xSemaphoreTake(mutex, portMAX_DELAY);
// Wakeup();
// internalBuffer[0] = registerAddress;
// std::memcpy(internalBuffer + 1, data, size);
// auto ret = Write(deviceAddress, internalBuffer, size + 1, true);
// Sleep();
// xSemaphoreGive(mutex);
// return ret;
return TwiMaster::ErrorCodes::NoError;
}
//TwiMaster::ErrorCodes TwiMaster::Read(uint8_t deviceAddress, uint8_t* buffer, size_t size, bool stop) {
// twiBaseAddress->ADDRESS = deviceAddress;
// twiBaseAddress->TASKS_RESUME = 0x1UL;
// twiBaseAddress->RXD.PTR = (uint32_t) buffer;
// twiBaseAddress->RXD.MAXCNT = size;
//
// twiBaseAddress->TASKS_STARTRX = 1;
//
// while (!twiBaseAddress->EVENTS_RXSTARTED && !twiBaseAddress->EVENTS_ERROR)
// ;
// twiBaseAddress->EVENTS_RXSTARTED = 0x0UL;
//
// txStartedCycleCount = DWT->CYCCNT;
// uint32_t currentCycleCount;
// while (!twiBaseAddress->EVENTS_LASTRX && !twiBaseAddress->EVENTS_ERROR) {
// currentCycleCount = DWT->CYCCNT;
// if ((currentCycleCount - txStartedCycleCount) > HwFreezedDelay) {
// FixHwFreezed();
// return ErrorCodes::TransactionFailed;
// }
// }
// twiBaseAddress->EVENTS_LASTRX = 0x0UL;
//
// if (stop || twiBaseAddress->EVENTS_ERROR) {
// twiBaseAddress->TASKS_STOP = 0x1UL;
// while (!twiBaseAddress->EVENTS_STOPPED)
// ;
// twiBaseAddress->EVENTS_STOPPED = 0x0UL;
// } else {
// twiBaseAddress->TASKS_SUSPEND = 0x1UL;
// while (!twiBaseAddress->EVENTS_SUSPENDED)
// ;
// twiBaseAddress->EVENTS_SUSPENDED = 0x0UL;
// }
//
// if (twiBaseAddress->EVENTS_ERROR) {
// twiBaseAddress->EVENTS_ERROR = 0x0UL;
// }
// return ErrorCodes::NoError;
//}
//TwiMaster::ErrorCodes TwiMaster::Write(uint8_t deviceAddress, const uint8_t* data, size_t size, bool stop) {
// twiBaseAddress->ADDRESS = deviceAddress;
// twiBaseAddress->TASKS_RESUME = 0x1UL;
// twiBaseAddress->TXD.PTR = (uint32_t) data;
// twiBaseAddress->TXD.MAXCNT = size;
//
// twiBaseAddress->TASKS_STARTTX = 1;
//
// while (!twiBaseAddress->EVENTS_TXSTARTED && !twiBaseAddress->EVENTS_ERROR)
// ;
// twiBaseAddress->EVENTS_TXSTARTED = 0x0UL;
//
// txStartedCycleCount = DWT->CYCCNT;
// uint32_t currentCycleCount;
// while (!twiBaseAddress->EVENTS_LASTTX && !twiBaseAddress->EVENTS_ERROR) {
// currentCycleCount = DWT->CYCCNT;
// if ((currentCycleCount - txStartedCycleCount) > HwFreezedDelay) {
// FixHwFreezed();
// return ErrorCodes::TransactionFailed;
// }
// }
// twiBaseAddress->EVENTS_LASTTX = 0x0UL;
//
// if (stop || twiBaseAddress->EVENTS_ERROR) {
// twiBaseAddress->TASKS_STOP = 0x1UL;
// while (!twiBaseAddress->EVENTS_STOPPED)
// ;
// twiBaseAddress->EVENTS_STOPPED = 0x0UL;
// } else {
// twiBaseAddress->TASKS_SUSPEND = 0x1UL;
// while (!twiBaseAddress->EVENTS_SUSPENDED)
// ;
// twiBaseAddress->EVENTS_SUSPENDED = 0x0UL;
// }
//
// if (twiBaseAddress->EVENTS_ERROR) {
// twiBaseAddress->EVENTS_ERROR = 0x0UL;
// uint32_t error = twiBaseAddress->ERRORSRC;
// twiBaseAddress->ERRORSRC = error;
// }
//
// return ErrorCodes::NoError;
//}
void TwiMaster::Sleep() {
// twiBaseAddress->ENABLE = (TWIM_ENABLE_ENABLE_Disabled << TWIM_ENABLE_ENABLE_Pos);
}
void TwiMaster::Wakeup() {
// twiBaseAddress->ENABLE = (TWIM_ENABLE_ENABLE_Enabled << TWIM_ENABLE_ENABLE_Pos);
}
/* Sometimes, the TWIM device just freeze and never set the event EVENTS_LASTTX.
* This method disable and re-enable the peripheral so that it works again.
* This is just a workaround, and it would be better if we could find a way to prevent
* this issue from happening.
* */
//void TwiMaster::FixHwFreezed() {
// NRF_LOG_INFO("I2C device frozen, reinitializing it!");
//
// uint32_t twi_state = NRF_TWI1->ENABLE;
//
// Sleep();
//
// twiBaseAddress->ENABLE = twi_state;
//}

41
sim/drivers/TwiMaster.h Normal file
View File

@@ -0,0 +1,41 @@
#pragma once
#include <FreeRTOS.h>
//#include <semphr.h>
#include <drivers/include/nrfx_twi.h> // NRF_TWIM_Type
#include <cstdint>
namespace Pinetime {
namespace Drivers {
class TwiMaster {
public:
enum class ErrorCodes { NoError, TransactionFailed };
TwiMaster(NRF_TWIM_Type* module, uint32_t frequency, uint8_t pinSda, uint8_t pinScl);
void Init();
ErrorCodes Read(uint8_t deviceAddress, uint8_t registerAddress, uint8_t* buffer, size_t size);
ErrorCodes Write(uint8_t deviceAddress, uint8_t registerAddress, const uint8_t* data, size_t size);
void Sleep();
void Wakeup();
private:
// ErrorCodes Read(uint8_t deviceAddress, uint8_t* buffer, size_t size, bool stop);
// ErrorCodes Write(uint8_t deviceAddress, const uint8_t* data, size_t size, bool stop);
// void FixHwFreezed();
// void ConfigurePins() const;
NRF_TWIM_Type* twiBaseAddress;
// SemaphoreHandle_t mutex = nullptr;
NRF_TWIM_Type* module;
uint32_t frequency;
uint8_t pinSda;
uint8_t pinScl;
static constexpr uint8_t maxDataSize {16};
static constexpr uint8_t registerSize {1};
uint8_t internalBuffer[maxDataSize + registerSize];
uint32_t txStartedCycleCount = 0;
static constexpr uint32_t HwFreezedDelay {161000};
};
}
}

41
sim/drivers/Watchdog.cpp Normal file
View File

@@ -0,0 +1,41 @@
#include "drivers/Watchdog.h"
using namespace Pinetime::Drivers;
void Watchdog::Setup(uint8_t timeoutSeconds) {
resetReason = ActualResetReason();
}
void Watchdog::Start() {
}
void Watchdog::Kick() {
}
Watchdog::ResetReasons Watchdog::ActualResetReason() const {
return ResetReasons::ResetPin;
}
const char* Watchdog::ResetReasonToString(Watchdog::ResetReasons reason) {
switch (reason) {
case ResetReasons::ResetPin:
return "Reset pin";
case ResetReasons::Watchdog:
return "Watchdog";
case ResetReasons::DebugInterface:
return "Debug interface";
case ResetReasons::LpComp:
return "LPCOMP";
case ResetReasons::SystemOff:
return "System OFF";
case ResetReasons::CpuLockup:
return "CPU Lock-up";
case ResetReasons::SoftReset:
return "Soft reset";
case ResetReasons::NFC:
return "NFC";
case ResetReasons::HardReset:
return "Hard reset";
default:
return "Unknown";
}
}

34
sim/drivers/Watchdog.h Normal file
View File

@@ -0,0 +1,34 @@
#pragma once
#include <cstdint>
namespace Pinetime {
namespace Drivers {
class Watchdog {
public:
enum class ResetReasons { ResetPin, Watchdog, SoftReset, CpuLockup, SystemOff, LpComp, DebugInterface, NFC, HardReset };
void Setup(uint8_t timeoutSeconds);
void Start();
void Kick();
ResetReasons ResetReason() const {
return resetReason;
}
static const char* ResetReasonToString(ResetReasons reason);
private:
ResetReasons resetReason;
ResetReasons ActualResetReason() const;
};
class WatchdogView {
public:
WatchdogView(const Watchdog& watchdog) : watchdog {watchdog} {
}
Watchdog::ResetReasons ResetReason() const {
return watchdog.ResetReason();
}
private:
const Watchdog& watchdog;
};
}
}