Initial work on SAMD

This commit is contained in:
Scott Shawcroft 2020-03-12 23:05:12 -07:00
parent affd3fcc2a
commit 48b5f2a384
No known key found for this signature in database
GPG Key ID: 9349BC7E64B1921E
19 changed files with 139 additions and 316 deletions

View File

@ -194,7 +194,6 @@ SRC_ASF := \
hpl/gclk/hpl_gclk.c \
hpl/nvmctrl/hpl_nvmctrl.c \
hpl/pm/hpl_pm.c \
hpl/rtc/hpl_rtc.c \
hpl/sercom/hpl_sercom.c \
hpl/systick/hpl_systick.c \
hal/utils/src/utils_list.c \
@ -258,7 +257,6 @@ SRC_C = \
peripherals/samd/timers.c \
reset.c \
supervisor/shared/memory.c \
tick.c \
timer_handler.c \

View File

@ -26,7 +26,6 @@
#include "background.h"
#include "audio_dma.h"
#include "tick.h"
#include "supervisor/filesystem.h"
#include "supervisor/shared/tick.h"
#include "supervisor/usb.h"
@ -34,6 +33,7 @@
#include "py/runtime.h"
#include "shared-module/network/__init__.h"
#include "supervisor/shared/stack.h"
#include "supervisor/port.h"
#ifdef CIRCUITPY_DISPLAYIO
#include "shared-module/displayio/__init__.h"
@ -92,10 +92,10 @@ void run_background_tasks(void) {
running_background_tasks = false;
assert_heap_ok();
last_finished_tick = supervisor_ticks_ms64();
last_finished_tick = port_get_raw_ticks(NULL);
finish_background_task();
}
bool background_tasks_ok(void) {
return supervisor_ticks_ms64() - last_finished_tick < 1000;
return port_get_raw_ticks(NULL) - last_finished_tick < 1024;
}

View File

@ -49,7 +49,6 @@
#include "samd/dma.h"
#include "audio_dma.h"
#include "tick.h"
#define OVERSAMPLING 64
#define SAMPLES_PER_BUFFER 32

View File

@ -33,8 +33,6 @@
#include "shared-bindings/digitalio/DigitalInOut.h"
#include "shared-bindings/microcontroller/__init__.h"
#include "tick.h"
void common_hal_displayio_parallelbus_construct(displayio_parallelbus_obj_t* self,
const mcu_pin_obj_t* data0, const mcu_pin_obj_t* command, const mcu_pin_obj_t* chip_select,
const mcu_pin_obj_t* write, const mcu_pin_obj_t* read, const mcu_pin_obj_t* reset) {

View File

@ -29,7 +29,7 @@
#include "shared-bindings/neopixel_write/__init__.h"
#include "tick.h"
#include "supervisor/port.h"
#ifdef SAMD51
#include "hri/hri_cmcc_d51.h"
@ -91,8 +91,7 @@ static void neopixel_send_buffer_core(volatile uint32_t *clraddr, uint32_t pinMa
"");
}
uint64_t next_start_tick_ms = 0;
uint32_t next_start_tick_us = 1000;
uint64_t next_start_raw_ticks = 0;
void common_hal_neopixel_write(const digitalio_digitalinout_obj_t* digitalinout, uint8_t *pixels, uint32_t numBytes) {
// This is adapted directly from the Adafruit NeoPixel library SAMD21G18A code:
@ -101,9 +100,9 @@ void common_hal_neopixel_write(const digitalio_digitalinout_obj_t* digitalinout,
uint32_t pinMask;
PortGroup* port;
// This must be called while interrupts are on in case we're waiting for a
// future ms tick.
wait_until(next_start_tick_ms, next_start_tick_us);
// Wait to make sure we don't append onto the last transmission. This should only be a tick or
// two.
while (port_get_raw_ticks(NULL) < next_start_raw_ticks) {}
// Turn off interrupts of any kind during timing-sensitive code.
mp_hal_disable_all_interrupts();
@ -144,15 +143,8 @@ void common_hal_neopixel_write(const digitalio_digitalinout_obj_t* digitalinout,
#endif
// ticks_ms may be out of date at this point because we stopped the
// interrupt. We'll risk it anyway.
current_tick(&next_start_tick_ms, &next_start_tick_us);
if (next_start_tick_us < 100) {
next_start_tick_ms += 1;
next_start_tick_us = 100 - next_start_tick_us;
} else {
next_start_tick_us -= 100;
}
// Update the next start.
next_start_raw_ticks = port_get_raw_ticks(NULL) + 4;
// Turn on interrupts after timing-sensitive code.
mp_hal_enable_all_interrupts();

View File

@ -41,10 +41,9 @@
#include "samd/pins.h"
#include "shared-bindings/microcontroller/__init__.h"
#include "shared-bindings/ps2io/Ps2.h"
#include "supervisor/port.h"
#include "supervisor/shared/translate.h"
#include "tick.h"
#define STATE_IDLE 0
#define STATE_RECV 1
#define STATE_RECV_PARITY 2
@ -168,24 +167,21 @@ static void delay_us(uint32_t t) {
void ps2_interrupt_handler(uint8_t channel) {
// Grab the current time first.
uint32_t current_us;
uint64_t current_ms;
current_tick(&current_ms, &current_us);
uint64_t current_tick = port_get_raw_ticks(NULL);
ps2io_ps2_obj_t* self = get_eic_channel_data(channel);
int data_bit = gpio_get_pin_level(self->data_pin) ? 1 : 0;
// test for timeout
if (self->state != STATE_IDLE) {
int64_t diff_ms = current_ms - self->last_int_ms;
if (diff_ms >= 2) { // a.k.a. > 1.001ms
int64_t diff_ms = current_tick - self->last_raw_ticks;
if (diff_ms > 1) { // a.k.a. > 1.001ms
self->last_errors |= ERROR_TIMEOUT;
self->state = STATE_IDLE;
}
}
self->last_int_us = current_us;
self->last_int_ms = current_ms;
self->last_raw_ticks = current_tick;
if (self->state == STATE_IDLE) {
self->bits = 0;

View File

@ -39,8 +39,7 @@ typedef struct {
uint8_t data_pin;
uint8_t state;
uint64_t last_int_ms;
uint32_t last_int_us;
uint64_t last_raw_ticks;
uint16_t bits;
bool parity;

View File

@ -42,8 +42,6 @@
#include "shared-bindings/pulseio/PulseIn.h"
#include "supervisor/shared/translate.h"
#include "tick.h"
static void pulsein_set_config(pulseio_pulsein_obj_t* self, bool first_edge) {
uint32_t sense_setting;
if (!first_edge) {
@ -61,9 +59,9 @@ static void pulsein_set_config(pulseio_pulsein_obj_t* self, bool first_edge) {
void pulsein_interrupt_handler(uint8_t channel) {
// Grab the current time first.
uint32_t current_us;
uint64_t current_ms;
current_tick(&current_ms, &current_us);
uint32_t current_us = 0;
uint64_t current_ms = 0;
// current_tick(&current_ms, &current_us);
// current_tick gives us the remaining us until the next tick but we want the number since the
// last ms.

View File

@ -30,76 +30,46 @@
#include <hal_init.h>
#include <hpl_gclk_base.h>
#include <hpl_pm_base.h>
#include <hal_calendar.h>
#include "py/obj.h"
#include "py/runtime.h"
#include "lib/timeutils/timeutils.h"
#include "shared-bindings/rtc/__init__.h"
#include "supervisor/port.h"
#include "supervisor/shared/translate.h"
static struct calendar_descriptor calendar;
void rtc_init(void) {
#ifdef SAMD21
_gclk_enable_channel(RTC_GCLK_ID, CONF_GCLK_RTC_SRC);
#endif
#ifdef SAMD51
hri_mclk_set_APBAMASK_RTC_bit(MCLK);
#endif
calendar_init(&calendar, RTC);
calendar_set_baseyear(&calendar, 2000);
calendar_enable(&calendar);
}
// This is the time in seconds since 2000 that the RTC was started.
static uint32_t rtc_offset = 0;
void common_hal_rtc_get_time(timeutils_struct_time_t *tm) {
struct calendar_date_time datetime;
calendar_get_date_time(&calendar, &datetime);
tm->tm_year = datetime.date.year;
tm->tm_mon = datetime.date.month;
tm->tm_mday = datetime.date.day;
tm->tm_hour = datetime.time.hour;
tm->tm_min = datetime.time.min;
tm->tm_sec = datetime.time.sec;
uint64_t ticks_s = port_get_raw_ticks(NULL) / 1024;
timeutils_seconds_since_2000_to_struct_time(rtc_offset + ticks_s, tm);
}
void common_hal_rtc_set_time(timeutils_struct_time_t *tm) {
// Reset prescaler to increase initial precision. Otherwise we can be up to 1 second off already.
uint32_t freqcorr = hri_rtcmode0_read_FREQCORR_reg(calendar.device.hw);
calendar_deinit(&calendar);
rtc_init();
hri_rtcmode0_write_FREQCORR_reg(calendar.device.hw, freqcorr);
struct calendar_date date = {
.year = tm->tm_year,
.month = tm->tm_mon,
.day = tm->tm_mday,
};
calendar_set_date(&calendar, &date);
struct calendar_time time = {
.hour = tm->tm_hour,
.min = tm->tm_min,
.sec = tm->tm_sec,
};
calendar_set_time(&calendar, &time);
uint64_t ticks_s = port_get_raw_ticks(NULL) / 1024;
uint32_t epoch_s = timeutils_seconds_since_2000(
tm->tm_year, tm->tm_mon, tm->tm_mday, tm->tm_hour, tm->tm_min, tm->tm_sec
);
rtc_offset = epoch_s - ticks_s;
}
// A positive value speeds up the clock by removing clock cycles.
int common_hal_rtc_get_calibration(void) {
int calibration = hri_rtcmode0_read_FREQCORR_VALUE_bf(calendar.device.hw);
int calibration = hri_rtcmode0_read_FREQCORR_VALUE_bf(RTC);
if (!hri_rtcmode0_get_FREQCORR_SIGN_bit(calendar.device.hw))
if (!hri_rtcmode0_get_FREQCORR_SIGN_bit(RTC)) {
calibration = -calibration;
}
return calibration;
}
void common_hal_rtc_set_calibration(int calibration) {
if (calibration > 127 || calibration < -127)
if (calibration > 127 || calibration < -127) {
mp_raise_ValueError(translate("calibration value out of range +/-127"));
}
hri_rtcmode0_write_FREQCORR_SIGN_bit(calendar.device.hw, calibration < 0 ? 0 : 1);
hri_rtcmode0_write_FREQCORR_VALUE_bf(calendar.device.hw, abs(calibration));
hri_rtcmode0_write_FREQCORR_SIGN_bit(RTC, calibration < 0 ? 0 : 1);
hri_rtcmode0_write_FREQCORR_VALUE_bf(RTC, abs(calibration));
}

View File

@ -27,6 +27,4 @@
#ifndef MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_RTC_RTC_H
#define MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_RTC_RTC_H
extern void rtc_init(void);
#endif // MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_RTC_RTC_H

View File

@ -1,48 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "py/mphal.h"
#include "shared-bindings/time/__init__.h"
#include "supervisor/shared/tick.h"
#include "tick.h"
inline uint64_t common_hal_time_monotonic(void) {
return supervisor_ticks_ms64();
}
uint64_t common_hal_time_monotonic_ns(void) {
uint64_t ms;
uint32_t us_until_ms;
current_tick(&ms, &us_until_ms);
// us counts down.
return 1000 * (ms * 1000 + (1000 - us_until_ms));
}
void common_hal_time_delay_ms(uint32_t delay) {
mp_hal_delay_ms(delay);
}

View File

@ -49,21 +49,6 @@
extern uint32_t common_hal_mcu_processor_get_frequency(void);
void mp_hal_delay_ms(mp_uint_t delay) {
uint64_t start_tick = supervisor_ticks_ms64();
uint64_t duration = 0;
while (duration < delay) {
RUN_BACKGROUND_TASKS;
// Check to see if we've been CTRL-Ced by autoreload or the user.
if(MP_STATE_VM(mp_pending_exception) == MP_OBJ_FROM_PTR(&MP_STATE_VM(mp_kbd_exception)) ||
MP_STATE_VM(mp_pending_exception) == MP_OBJ_FROM_PTR(&MP_STATE_VM(mp_reload_exception))) {
break;
}
duration = (supervisor_ticks_ms64() - start_tick);
// TODO(tannewt): Go to sleep for a little while while we wait.
}
}
// Use mp_hal_delay_us() for timing of less than 1ms.
// Do a simple timing loop to wait for a certain number of microseconds.
// Can be used when interrupts are disabled, which makes tick_delay() unreliable.

View File

@ -70,10 +70,10 @@
#include "samd/dma.h"
#include "shared-bindings/rtc/__init__.h"
#include "reset.h"
#include "tick.h"
#include "supervisor/shared/safe_mode.h"
#include "supervisor/shared/stack.h"
#include "supervisor/shared/tick.h"
#include "tusb.h"
@ -132,6 +132,38 @@ static void save_usb_clock_calibration(void) {
}
#endif
static void rtc_init(void) {
#ifdef SAMD21
_gclk_enable_channel(RTC_GCLK_ID, CONF_GCLK_RTC_SRC);
#endif
#ifdef SAMD51
hri_mclk_set_APBAMASK_RTC_bit(MCLK);
#endif
RTC->MODE0.CTRLA.reg = RTC_MODE0_CTRLA_ENABLE |
RTC_MODE0_CTRLA_MODE_COUNT32 |
RTC_MODE0_CTRLA_PRESCALER_DIV2 |
RTC_MODE0_CTRLA_COUNTSYNC;
RTC->MODE0.INTENSET.reg = RTC_MODE0_INTENSET_OVF;
// Set all peripheral interrupt priorities to the lowest priority by default.
for (uint16_t i = 0; i < PERIPH_COUNT_IRQn; i++) {
NVIC_SetPriority(i, (1UL << __NVIC_PRIO_BITS) - 1UL);
}
// Bump up the rtc interrupt so nothing else interferes with timekeeping.
NVIC_SetPriority(RTC_IRQn, 0);
#ifdef SAMD21
NVIC_SetPriority(USB_IRQn, 1);
#endif
#ifdef SAMD51
NVIC_SetPriority(USB_0_IRQn, 1);
NVIC_SetPriority(USB_1_IRQn, 1);
NVIC_SetPriority(USB_2_IRQn, 1);
NVIC_SetPriority(USB_3_IRQn, 1);
#endif
}
safe_mode_t port_init(void) {
#if defined(SAMD21)
@ -220,12 +252,7 @@ safe_mode_t port_init(void) {
clock_init(BOARD_HAS_CRYSTAL, DEFAULT_DFLL48M_FINE_CALIBRATION);
#endif
// Configure millisecond timer initialization.
tick_init();
#if CIRCUITPY_RTC
rtc_init();
#endif
init_shared_dma();
@ -275,9 +302,6 @@ void reset_port(void) {
analogin_reset();
analogout_reset();
#endif
#if CIRCUITPY_RTC
rtc_reset();
#endif
reset_gclks();
@ -352,6 +376,70 @@ uint32_t port_get_saved_word(void) {
return *safe_word;
}
// TODO: Move this to an RTC backup register so we can preserve it when only the BACKUP power domain
// is enabled.
static volatile uint64_t overflowed_ticks = 0;
void RTC_Handler(void) {
uint32_t intflag = RTC->MODE0.INTFLAG.reg;
if (intflag & RTC_MODE0_INTFLAG_OVF) {
RTC->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_OVF;
// Our RTC is 32 bits and we're clocking it at 16.384khz which is 16 (2 ** 4) subticks per
// tick.
overflowed_ticks += (1L<< (32 - 4));
} else if (intflag & RTC_MODE0_INTFLAG_PER2) {
RTC->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_PER2;
// Do things common to all ports when the tick occurs
supervisor_tick();
} else if (intflag & RTC_MODE0_INTFLAG_CMP0) {
RTC->MODE0.INTENCLR.reg = RTC_MODE0_INTENCLR_CMP0;
RTC->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0;
}
}
uint64_t port_get_raw_ticks(uint8_t* subticks) {
while ((RTC->MODE0.SYNCBUSY.reg & (RTC_MODE0_SYNCBUSY_COUNTSYNC | RTC_MODE0_SYNCBUSY_COUNT)) != 0) {}
uint32_t current_ticks = RTC->MODE0.COUNT.reg;
if (subticks != NULL) {
*subticks = (current_ticks % 16) * 2;
}
return overflowed_ticks + current_ticks / 16;
}
// Enable 1/1024 second tick.
void port_enable_tick(void) {
// PER2 will generate an interrupt every 32 ticks of the source 32.768 clock.
RTC->MODE0.INTENSET.reg = RTC_MODE0_INTFLAG_PER2;
}
// Disable 1/1024 second tick.
void port_disable_tick(void) {
RTC->MODE0.INTENCLR.reg = RTC_MODE0_INTFLAG_PER2;
}
void port_interrupt_after_ticks(uint32_t ticks) {
while ((RTC->MODE0.SYNCBUSY.reg & (RTC_MODE0_SYNCBUSY_COUNTSYNC | RTC_MODE0_SYNCBUSY_COUNT)) != 0) {}
uint32_t current_ticks = RTC->MODE0.COUNT.reg;
if (ticks > 1 << 28) {
// We'll interrupt sooner with an overflow.
return;
}
RTC->MODE0.COMP[0].reg = current_ticks + (ticks << 4);
RTC->MODE0.INTENSET.reg = RTC_MODE0_INTENSET_CMP0;
}
void port_sleep_until_interrupt(void) {
// Clear the FPU interrupt because it can prevent us from sleeping.
if (__get_FPSCR() & ~(0x9f)) {
__set_FPSCR(__get_FPSCR() & ~(0x9f));
(void) __get_FPSCR();
}
// Call wait for interrupt ourselves if the SD isn't enabled.
__WFI();
}
/**
* \brief Default interrupt handler for unused IRQs.
*/

View File

@ -1,107 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "tick.h"
#include "peripheral_clk_config.h"
#include "supervisor/shared/tick.h"
#include "shared-bindings/microcontroller/__init__.h"
#include "shared-bindings/microcontroller/Processor.h"
void SysTick_Handler(void) {
// SysTick interrupt handler called when the SysTick timer reaches zero
// (every millisecond).
common_hal_mcu_disable_interrupts();
// Read the control register to reset the COUNTFLAG.
(void) SysTick->CTRL;
common_hal_mcu_enable_interrupts();
// Do things common to all ports when the tick occurs
supervisor_tick();
}
void tick_init() {
uint32_t ticks_per_ms = common_hal_mcu_processor_get_frequency() / 1000;
SysTick_Config(ticks_per_ms-1);
NVIC_EnableIRQ(SysTick_IRQn);
// Set all peripheral interrupt priorities to the lowest priority by default.
for (uint16_t i = 0; i < PERIPH_COUNT_IRQn; i++) {
NVIC_SetPriority(i, (1UL << __NVIC_PRIO_BITS) - 1UL);
}
// Bump up the systick interrupt so nothing else interferes with timekeeping.
NVIC_SetPriority(SysTick_IRQn, 0);
#ifdef SAMD21
NVIC_SetPriority(USB_IRQn, 1);
#endif
#ifdef SAMD51
NVIC_SetPriority(USB_0_IRQn, 1);
NVIC_SetPriority(USB_1_IRQn, 1);
NVIC_SetPriority(USB_2_IRQn, 1);
NVIC_SetPriority(USB_3_IRQn, 1);
#endif
}
void tick_delay(uint32_t us) {
uint32_t ticks_per_us = common_hal_mcu_processor_get_frequency() / 1000 / 1000;
uint32_t us_until_next_tick = SysTick->VAL / ticks_per_us;
uint32_t start_tick;
while (us >= us_until_next_tick) {
start_tick = SysTick->VAL; // wait for SysTick->VAL to RESET
while (SysTick->VAL < start_tick) {}
us -= us_until_next_tick;
us_until_next_tick = 1000;
}
while (SysTick->VAL > ((us_until_next_tick - us) * ticks_per_us)) {}
}
// us counts down!
void current_tick(uint64_t* ms, uint32_t* us_until_ms) {
uint32_t ticks_per_us = common_hal_mcu_processor_get_frequency() / 1000 / 1000;
// We disable interrupts to prevent ticks_ms from changing while we grab it.
common_hal_mcu_disable_interrupts();
uint32_t tick_status = SysTick->CTRL;
uint32_t current_us = SysTick->VAL;
uint32_t tick_status2 = SysTick->CTRL;
uint64_t current_ms = supervisor_ticks_ms64();
// The second clause ensures our value actually rolled over. Its possible it hit zero between
// the VAL read and CTRL read.
if ((tick_status & SysTick_CTRL_COUNTFLAG_Msk) != 0 ||
((tick_status2 & SysTick_CTRL_COUNTFLAG_Msk) != 0 && current_us > ticks_per_us)) {
current_ms++;
}
common_hal_mcu_enable_interrupts();
*ms = current_ms;
*us_until_ms = current_us / ticks_per_us;
}
void wait_until(uint64_t ms, uint32_t us_until_ms) {
uint32_t ticks_per_us = common_hal_mcu_processor_get_frequency() / 1000 / 1000;
while (supervisor_ticks_ms64() <= ms && SysTick->VAL / ticks_per_us >= us_until_ms) {}
}

View File

@ -1,42 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2017 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef MICROPY_INCLUDED_ATMEL_SAMD_TICK_H
#define MICROPY_INCLUDED_ATMEL_SAMD_TICK_H
#include "py/mpconfig.h"
extern struct timer_descriptor ms_timer;
void tick_init(void);
void tick_delay(uint32_t us);
void current_tick(uint64_t* ms, uint32_t* us_until_ms);
// Do not call this with interrupts disabled because it may be waiting for
// ticks_ms to increment.
void wait_until(uint64_t ms, uint32_t us_until_ms);
#endif // MICROPY_INCLUDED_ATMEL_SAMD_TICK_H

View File

@ -33,9 +33,6 @@
#include "supervisor/port.h"
#include "supervisor/shared/translate.h"
#include "nrfx_rtc.h"
#include "nrf_clock.h"
// This is the time in seconds since 2000 that the RTC was started.
static uint32_t rtc_offset = 0;

View File

@ -78,7 +78,9 @@ static volatile uint64_t overflowed_ticks = 0;
void rtc_handler(nrfx_rtc_int_type_t int_type) {
if (int_type == NRFX_RTC_INT_OVERFLOW) {
overflowed_ticks += (1L<<24);
// Our RTC is 24 bits and we're clocking it at 32.768khz which is 32 (2 ** 5) subticks per
// tick.
overflowed_ticks += (1L<< (24 - 5));
} else if (int_type == NRFX_RTC_INT_TICK && nrfx_rtc_counter_get(&rtc_instance) % 32 == 0) {
// Do things common to all ports when the tick occurs
supervisor_tick();

View File

@ -282,8 +282,7 @@ SRC_COMMON_HAL_ALL = \
rtc/RTC.c \
rtc/__init__.c \
supervisor/Runtime.c \
supervisor/__init__.c \
time/__init__.c
supervisor/__init__.c
SRC_COMMON_HAL = $(filter $(SRC_PATTERNS), $(SRC_COMMON_HAL_ALL))
@ -358,6 +357,7 @@ SRC_SHARED_MODULE_ALL = \
network/__init__.c \
storage/__init__.c \
struct/__init__.c \
time/__init__.c \
terminalio/Terminal.c \
terminalio/__init__.c \
uheap/__init__.c \