Merge 2.1.0 changes into master.

This commit is contained in:
Dan Halbert 2017-10-23 12:29:17 -04:00 committed by Scott Shawcroft
parent 1c97b7f4df
commit 6df99b5d0e
29 changed files with 137 additions and 128 deletions

View File

@ -101,11 +101,9 @@ else
# -finline-limit can shrink the image size.
# -finline-limit=80 or so is similar to not having it on.
# There is no simple default value, though.
ifeq ($(FLASH_IMPL),internal_flash.c)
ifeq ($(CHIP_FAMILY), samd21)
### TODO(dhalbert): disable for now; breaks things in 3.0.0 build(e.g. deinit checking is disabled)
# CFLAGS += -finline-limit=19
endif
ifdef INTERNAL_FLASH_FILESYSTEM
## Not currently needed
## CFLAGS += -finline-limit=50
endif
CFLAGS += -flto
endif
@ -151,18 +149,19 @@ CFLAGS += -DMICROPY_MODULE_FROZEN_MPY
CFLAGS += -Wno-error=lto-type-mismatch
endif
#LIBM_FILE_NAME = $(shell $(CC) $(CFLAGS) -print-file-name=libm.a)
LDFLAGS = $(CFLAGS) -nostartfiles -fshort-enums -Wl,-nostdlib -Wl,-T,$(LD_FILE) -Wl,-Map=$@.map -Wl,-cref -Wl,-gc-sections -specs=nano.specs
LIBS := -lgcc -lc
# Use toolchain libm if we're not using our own.
ifndef INTERNAL_LIBM
LIBS += -lm
endif
ifeq ($(CHIP_FAMILY), samd21)
LDFLAGS += -mthumb -mcpu=cortex-m0plus -Lasf/thirdparty/CMSIS/Lib/GCC/
LIBS := -lm $(LIBS) # -larm_cortexM0l_math
BOOTLOADER_SIZE := 0x2000
else ifeq ($(CHIP_FAMILY), samd51)
LDFLAGS += -mthumb -mcpu=cortex-m4
LIBS := -lm $(LIBS)
BOOTLOADER_SIZE := 0x4000
endif
@ -220,7 +219,6 @@ SRC_C = \
tick.c \
usb.c \
usb_mass_storage.c \
$(FLASH_IMPL) \
bindings/samd/__init__.c \
boards/$(BOARD)/board.c \
boards/$(BOARD)/pins.c \
@ -235,7 +233,17 @@ SRC_C = \
lib/utils/sys_stdio_mphal.c \
lib/libc/string0.c \
lib/mp-readline/readline.c \
# freetouch/adafruit_ptc.c \
# freetouch/adafruit_ptc.c
# Choose which flash filesystem impl to use.
# (Right now INTERNAL_FLASH_FILESYSTEM and SPI_FLASH_FILESYSTEM are mutually exclusive.
# But that might not be true in the future.)
ifdef INTERNAL_FLASH_FILESYSTEM
SRC_C += internal_flash.c
endif
ifdef SPI_FLASH_FILESYSTEM
SRC_C += spi_flash.c
endif
SRC_COMMON_HAL = \
board/__init__.c \
@ -270,6 +278,30 @@ SRC_COMMON_HAL = \
usb_hid/__init__.c \
usb_hid/Device.c
ifdef INTERNAL_LIBM
SRC_LIBM = $(addprefix lib/,\
libm/math.c \
libm/fmodf.c \
libm/nearbyintf.c \
libm/ef_sqrt.c \
libm/kf_rem_pio2.c \
libm/kf_sin.c \
libm/kf_cos.c \
libm/kf_tan.c \
libm/ef_rem_pio2.c \
libm/sf_sin.c \
libm/sf_cos.c \
libm/sf_tan.c \
libm/sf_frexp.c \
libm/sf_modf.c \
libm/sf_ldexp.c \
libm/asinfacosf.c \
libm/atanf.c \
libm/atan2f.c \
)
endif
# These don't have corresponding files in each port but are still located in
# shared-bindings to make it clear what the contents of the modules are.
SRC_BINDINGS_ENUMS = \
@ -306,6 +338,9 @@ OBJ = $(PY_O) $(SUPERVISOR_O) $(addprefix $(BUILD)/, $(SRC_C:.c=.o))
OBJ += $(addprefix $(BUILD)/, $(SRC_ASF:.c=.o))
OBJ += $(addprefix $(BUILD)/, $(SRC_COMMON_HAL_EXPANDED:.c=.o))
OBJ += $(addprefix $(BUILD)/, $(SRC_SHARED_MODULE_EXPANDED:.c=.o))
ifdef INTERNAL_LIBM
OBJ += $(addprefix $(BUILD)/, $(SRC_LIBM:.c=.o))
endif
SRC_QSTR += $(SRC_C) $(SRC_SUPERVISOR) $(SRC_COMMON_HAL_EXPANDED) $(SRC_SHARED_MODULE_EXPANDED) $(STM_SRC_C)

View File

@ -2,7 +2,7 @@ LD_FILE = boards/samd21x18-bootloader.ld
USB_VID = 0x2341
USB_PID = 0x824D
FLASH_IMPL = internal_flash.c
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21G18A
CHIP_FAMILY = samd21

View File

@ -3,6 +3,9 @@
#define MICROPY_HW_BOARD_NAME "Adafruit CircuitPlayground Express"
#define MICROPY_HW_MCU_NAME "samd21g18"
// Don't allow touch on A0 (PA02), because it's connected to the speaker.
#define PA02_NO_TOUCH (true)
// Salae reads 12mhz which is the limit even though we set it to the safer 8mhz.
#define SPI_FLASH_BAUDRATE (8000000)

View File

@ -2,8 +2,8 @@ LD_FILE = boards/samd21x18-bootloader-crystalless.ld
USB_VID = 0x239A
USB_PID = 0x8019
#FLASH_IMPL = spi_flash.c
FLASH_IMPL = internal_flash.c
#SPI_FLASH_FILESYSTEM = 1
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21G18A
CHIP_FAMILY = samd21

View File

@ -2,7 +2,7 @@ LD_FILE = boards/samd21x18-bootloader.ld
USB_VID = 0x239A
USB_PID = 0x8015
FLASH_IMPL = internal_flash.c
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21G18A
CHIP_FAMILY = samd21

View File

@ -2,7 +2,7 @@ LD_FILE = boards/samd21x18-bootloader.ld
USB_VID = 0x239A
USB_PID = 0x8015
FLASH_IMPL = internal_flash.c
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21G18A
CHIP_FAMILY = samd21

View File

@ -2,8 +2,8 @@ LD_FILE = boards/samd21x18-bootloader.ld
USB_VID = 0x239A
USB_PID = 0x801b
#FLASH_IMPL = spi_flash.c
FLASH_IMPL = internal_flash.c
#SPI_FLASH_FILESYSTEM = 1
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21G18A
CHIP_FAMILY = samd21

View File

@ -2,7 +2,7 @@ LD_FILE = boards/samd21x18-bootloader.ld
USB_VID = 0x239A
USB_PID = 0x801D
FLASH_IMPL = internal_flash.c
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21E18A
CHIP_FAMILY = samd21

View File

@ -2,8 +2,8 @@ LD_FILE = boards/samd21x18-bootloader.ld
USB_VID = 0x239A
USB_PID = 0x8014
#FLASH_IMPL = spi_flash.c
FLASH_IMPL = internal_flash.c
#SPI_FLASH_FILESYSTEM = 1
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21G18A
CHIP_FAMILY = samd21

View File

@ -2,8 +2,8 @@ LD_FILE = boards/samd51x19-bootloader.ld
USB_VID = 0x239A
USB_PID = 0x8015
#FLASH_IMPL = spi_flash.c
FLASH_IMPL = internal_flash.c
#SPI_FLASH_FILESYSTEM = 1
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD51J19A
CHIP_FAMILY = samd51

View File

@ -2,7 +2,7 @@ LD_FILE = boards/samd21x18-bootloader.ld
USB_VID = 0x239A
USB_PID = 0x801F
FLASH_IMPL = internal_flash.c
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21E18A
CHIP_FAMILY = samd21

View File

@ -2,7 +2,8 @@ LD_FILE = boards/samd21x18-bootloader-external-flash-crystalless.ld
USB_VID = 0x239A
USB_PID = 0x801F
FLASH_IMPL = spi_flash.c
#SPI_FLASH_FILESYSTEM = 1
INTERNAL_FLASH_FILESYSTEM = 1
CHIP_VARIANT = SAMD21E18A
CHIP_FAMILY = samd21

View File

@ -38,13 +38,6 @@
#include "asf/sam0/drivers/adc/adc.h"
#include "samd21_pins.h"
// Number of active ADC channels.
volatile uint8_t active_channel_count;
// Shared between all the instances. Allocated only when needed.
struct adc_module *adc_instance = NULL;
struct adc_config *config_adc = NULL;
void common_hal_analogio_analogin_construct(analogio_analogin_obj_t* self,
const mcu_pin_obj_t *pin) {
if (!pin->has_adc) {
@ -54,27 +47,6 @@ void common_hal_analogio_analogin_construct(analogio_analogin_obj_t* self,
claim_pin(pin);
self->pin = pin;
if (adc_instance == NULL) {
// Allocate strucs on the heap so we only use the memory when we
// need it.
adc_instance = gc_alloc(sizeof(struct adc_module), false);
config_adc = gc_alloc(sizeof(struct adc_config), false);
adc_get_config_defaults(config_adc);
config_adc->reference = ADC_REFERENCE_INTVCC1;
config_adc->gain_factor = ADC_GAIN_FACTOR_DIV2;
config_adc->positive_input = self->pin->adc_input;
config_adc->resolution = ADC_RESOLUTION_16BIT;
config_adc->clock_prescaler = ADC_CLOCK_PRESCALER_DIV128;
adc_init(adc_instance, ADC, config_adc);
}
self->adc_instance = adc_instance;
self->config_adc = config_adc;
active_channel_count++;
}
bool common_hal_analogio_analogin_deinited(analogio_analogin_obj_t *self) {
@ -85,36 +57,30 @@ void common_hal_analogio_analogin_deinit(analogio_analogin_obj_t *self) {
if (common_hal_analogio_analogin_deinited(self)) {
return;
}
active_channel_count--;
if (active_channel_count == 0) {
adc_reset(adc_instance);
gc_free(adc_instance);
gc_free(config_adc);
// Set our references to NULL so the GC doesn't mistakenly see the
// pointers in memory.
adc_instance = NULL;
config_adc = NULL;
}
reset_pin(self->pin->pin);
self->pin = mp_const_none;
}
void analogin_reset() {
if (adc_instance != NULL) {
adc_reset(adc_instance);
adc_instance = NULL;
}
active_channel_count = 0;
}
uint16_t common_hal_analogio_analogin_get_value(analogio_analogin_obj_t *self) {
// Something else might have used the ADC in a different way,
// so we have to completely re-initialize it.
// ADC must have been disabled before adc_init() is called.
adc_init(adc_instance, ADC, config_adc);
config_adc->positive_input = self->pin->adc_input;
// so we completely re-initialize it.
adc_enable(adc_instance);
struct adc_config config_adc;
adc_get_config_defaults(&config_adc);
config_adc.reference = ADC_REFERENCE_INTVCC1;
config_adc.gain_factor = ADC_GAIN_FACTOR_DIV2;
config_adc.positive_input = self->pin->adc_input;
config_adc.resolution = ADC_RESOLUTION_16BIT;
config_adc.clock_prescaler = ADC_CLOCK_PRESCALER_DIV128;
struct adc_module adc_instance;
// ADC must have been disabled before adc_init() is called.
adc_init(&adc_instance, ADC, &config_adc);
adc_enable(&adc_instance);
// Read twice and discard first result, as recommended in section 14 of
// http://www.atmel.com/images/Atmel-42645-ADC-Configurations-with-Examples_ApplicationNote_AT11481.pdf
@ -125,23 +91,23 @@ uint16_t common_hal_analogio_analogin_get_value(analogio_analogin_obj_t *self) {
uint16_t data;
enum status_code status;
adc_start_conversion(adc_instance);
adc_start_conversion(&adc_instance);
do {
status = adc_read(adc_instance, &data);
status = adc_read(&adc_instance, &data);
} while (status == STATUS_BUSY);
if (status == STATUS_ERR_OVERFLOW) {
// TODO(tannewt): Throw an error.
mp_raise_RuntimeError("ADC result overwritten before reading");
}
adc_start_conversion(adc_instance);
adc_start_conversion(&adc_instance);
do {
status = adc_read(adc_instance, &data);
status = adc_read(&adc_instance, &data);
} while (status == STATUS_BUSY);
if (status == STATUS_ERR_OVERFLOW) {
// TODO(tannewt): Throw an error.
mp_raise_RuntimeError("ADC result overwritten before reading");
}
adc_disable(adc_instance);
adc_disable(&adc_instance);
return data;
}

View File

@ -34,8 +34,6 @@
typedef struct {
mp_obj_base_t base;
const mcu_pin_obj_t * pin;
struct adc_module * adc_instance;
struct adc_config * config_adc;
} analogio_analogin_obj_t;
void analogin_reset(void);

View File

@ -68,8 +68,12 @@ void common_hal_digitalio_digitalinout_switch_to_input(
void common_hal_digitalio_digitalinout_switch_to_output(
digitalio_digitalinout_obj_t* self, bool value,
enum digitalio_drive_mode_t drive_mode) {
gpio_set_pin_pull_mode(self->pin->pin, GPIO_PULL_OFF);
gpio_set_pin_direction(self->pin->pin, GPIO_DIRECTION_OUT);
const uint8_t pin = self->pin->pin;
gpio_set_pin_pull_mode(pin, GPIO_PULL_OFF);
gpio_set_pin_direction(pin, GPIO_DIRECTION_OUT);
// Turn on "strong" pin driving (more current available). See DRVSTR doc in datasheet.
hri_port_set_PINCFG_DRVSTR_bit(PORT, (enum gpio_port)GPIO_PORT(pin), pin);
self->output = true;
self->open_drain = drive_mode == DRIVE_MODE_OPEN_DRAIN;
@ -98,9 +102,9 @@ void common_hal_digitalio_digitalinout_set_value(
bool common_hal_digitalio_digitalinout_get_value(
digitalio_digitalinout_obj_t* self) {
uint32_t pin = self->pin->pin;
const uint8_t pin = self->pin->pin;
if (!self->output) {
return gpio_get_pin_level(self->pin->pin);
return gpio_get_pin_level(pin);
} else {
if (self->open_drain && hri_port_get_DIR_reg(PORT, (enum gpio_port)GPIO_PORT(pin), 1U << pin) == 0) {
return true;

View File

@ -204,6 +204,8 @@ extern const struct _mp_obj_module_t usb_hid_module;
#define MICROPY_PY_FRAMEBUF (0)
#define EXTRA_BUILTIN_MODULES
#define MICROPY_PY_BUILTINS_COMPLEX (0)
#define MICROPY_BUILTIN_METHOD_CHECK_SELF_ARG (0)
#define MICROPY_CPYTHON_COMPAT (0)
#endif

View File

@ -2,3 +2,6 @@
# $(MPY-TOOL) needs to know what kind of longint to use (if any) to freeze long integers.
# This should correspond to the MICROPY_LONGINT_IMPL definition in mpconfigport.h.
MPY_TOOL_LONGINT_IMPL = -mlongint-impl=none
INTERNAL_LIBM = (1)

View File

@ -105,7 +105,13 @@ PIN(PA01, EXTINT_CHANNEL(1), NO_ADC, NO_TOUCH,
NO_TIMER);
#endif
#ifdef PIN_PA02
PIN(PA02, EXTINT_CHANNEL(2), ADC_INPUT(0), TOUCH(0),
// Touch is not allowed on A0 (PA02) on Circuit Playground Express.
PIN(PA02, EXTINT_CHANNEL(2), ADC_INPUT(0),
#ifdef PA02_NO_TOUCH
NO_TOUCH,
#else
TOUCH(0),
#endif
NO_SERCOM,
NO_SERCOM,
NO_TIMER,

View File

@ -174,13 +174,13 @@ bool common_hal_busio_spi_read(busio_spi_obj_t *self,
write_value;
for (size_t j = 0; j < count; ++j) {
for (size_t k = 0; k < chunk_size; ++k) {
data[i] = spi_transaction(HSPI, 0, 0, 0, 0, 0, 0, 8, long_write_value);
data[i] = spi_transaction(HSPI, 0, 0, 0, 0, 8, long_write_value, 8, 0);
++i;
}
ets_loop_iter();
}
while (i < len) {
data[i] = spi_transaction(HSPI, 0, 0, 0, 0, 0, 0, 8, long_write_value);
data[i] = spi_transaction(HSPI, 0, 0, 0, 0, 8, long_write_value, 8, 0);
++i;
}
return true;

View File

@ -28,6 +28,8 @@
#include "common-hal/microcontroller/Pin.h"
#include "shared-bindings/microcontroller/Pin.h"
#include "py/mphal.h"
#include "eagle_soc.h"
extern volatile bool adc_in_use;
@ -48,11 +50,13 @@ bool common_hal_mcu_pin_is_free(const mcu_pin_obj_t* pin) {
void reset_pins(void) {
for (int i = 0; i < 17; i++) {
// 5 is RXD, 6 is TXD
if (i == 0 || (i > 4 && i < 13) || i == 12) {
if ((i > 4 && i < 13) || i == 12) {
continue;
}
uint32_t peripheral = PERIPHS_IO_MUX + i * 4;
PIN_FUNC_SELECT(peripheral, 0);
PIN_PULLUP_DIS(peripheral);
// Disable the pin.
gpio_output_set(0x0, 0x0, 0x0, 1 << i);
}
}

View File

@ -1,32 +0,0 @@
# NeoPixel driver for MicroPython on ESP8266
# MIT license; Copyright (c) 2016 Damien P. George
from esp import neopixel_write
class NeoPixel:
ORDER = (1, 0, 2, 3)
def __init__(self, pin, n, bpp=3):
self.pin = pin
self.n = n
self.bpp = bpp
self.buf = bytearray(n * bpp)
self.pin.init(pin.OUT)
def __setitem__(self, index, val):
offset = index * self.bpp
for i in range(self.bpp):
self.buf[offset + self.ORDER[i]] = val[i]
def __getitem__(self, index):
offset = index * self.bpp
return tuple(self.buf[offset + self.ORDER[i]]
for i in range(self.bpp))
def fill(self, color):
for i in range(self.n):
self[i] = color
def write(self):
neopixel_write(self.pin, self.buf, True)

View File

@ -173,6 +173,7 @@ extern const struct _mp_obj_module_t busio_module;
extern const struct _mp_obj_module_t bitbangio_module;
extern const struct _mp_obj_module_t time_module;
extern const struct _mp_obj_module_t multiterminal_module;
extern const struct _mp_obj_module_t neopixel_write_module;
#define MICROPY_PORT_BUILTIN_MODULES \
{ MP_OBJ_NEW_QSTR(MP_QSTR_esp), (mp_obj_t)&esp_module }, \
@ -195,6 +196,7 @@ extern const struct _mp_obj_module_t multiterminal_module;
{ MP_OBJ_NEW_QSTR(MP_QSTR_math), (mp_obj_t)&math_module }, \
{ MP_OBJ_NEW_QSTR(MP_QSTR_time), (mp_obj_t)&time_module }, \
{ MP_OBJ_NEW_QSTR(MP_QSTR_multiterminal), (mp_obj_t)&multiterminal_module }, \
{ MP_OBJ_NEW_QSTR(MP_QSTR_neopixel_write),(mp_obj_t)&neopixel_write_module }, \
#define MICROPY_PORT_BUILTIN_MODULE_WEAK_LINKS \
{ MP_ROM_QSTR(MP_QSTR_json), MP_ROM_PTR(&mp_module_ujson) }, \

View File

@ -151,7 +151,7 @@ pio2_3t = 6.1232342629e-17; /* 0x248d3132 */
fn = (float)n;
r = t-fn*pio2_1;
w = fn*pio2_1t; /* 1st round good to 40 bit */
if(n<32&&(ix&0xffffff00)!=npio2_hw[n-1]) {
if(n<32&&(__int32_t)(ix&0xffffff00)!=npio2_hw[n-1]) {
y[0] = r-w; /* quick check no cancellation */
} else {
__uint32_t high;
@ -195,7 +195,10 @@ pio2_3t = 6.1232342629e-17; /* 0x248d3132 */
}
tx[2] = z;
nx = 3;
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
while(tx[nx-1]==zero) nx--; /* skip zero term */
#pragma GCC diagnostic pop
n = __kernel_rem_pio2f(tx,y,e0,nx,2,two_over_pi);
if(hx<0) {y[0] = -y[0]; y[1] = -y[1]; return -n;}
return n;

View File

@ -138,7 +138,10 @@ recompute:
}
/* check if recomputation is needed */
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if(z==zero) {
#pragma GCC diagnostic pop
j = 0;
for (i=jz-1;i>=jk;i--) j |= iq[i];
if(j==0) { /* need recomputation */
@ -155,7 +158,10 @@ recompute:
}
/* chop off zero terms */
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if(z==(float)0.0) {
#pragma GCC diagnostic pop
jz -= 1; q0 -= 8;
while(iq[jz]==0) { jz--; q0-=8;}
} else { /* break z into 8-bit if necessary */

View File

@ -338,7 +338,7 @@ float powf(float x, float y)
return sn*huge*huge; /* overflow */
} else if ((j&0x7fffffff) > 0x43160000) /* z < -150 */ // FIXME: check should be (uint32_t)j > 0xc3160000
return sn*tiny*tiny; /* underflow */
else if (j == 0xc3160000) { /* z == -150 */
else if (j == (int32_t) 0xc3160000) { /* z == -150 */
if (p_l <= z-p_h)
return sn*tiny*tiny; /* underflow */
}
@ -585,13 +585,13 @@ float expm1f(float x)
/*****************************************************************************/
/*****************************************************************************/
/* k is such that k*ln2 has minimal relative error and x - kln2 > log(FLT_MIN) */
static const int k = 235;
static const float kln2 = 0x1.45c778p+7f;
/* expf(x)/2 for x >= log(FLT_MAX), slightly better than 0.5f*expf(x/2)*expf(x/2) */
float __expo2f(float x)
{
/* k is such that k*ln2 has minimal relative error and x - kln2 > log(FLT_MIN) */
static const int k = 235;
static const float kln2 = 0x1.45c778p+7f;
float scale;
/* note that k is odd and scale*scale overflows */

View File

@ -15,7 +15,10 @@ float nearbyintf(float x)
y = x - 0x1p23f + 0x1p23f;
else
y = x + 0x1p23f - 0x1p23f;
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if (y == 0)
#pragma GCC diagnostic pop
return s ? -0.0f : 0.0f;
return y;
}

View File

@ -32,7 +32,10 @@
float value; int exp;
#endif
{
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if(!isfinite(value)||value==(float)0.0) return value;
#pragma GCC diagnostic pop
value = scalbnf(value,exp);
//if(!finitef(value)||value==(float)0.0) errno = ERANGE;
return value;

View File

@ -28,7 +28,7 @@ Module / Port SAMD21 SAMD21 Express ESP8266
`neopixel_write` **Yes** **Yes** **Yes**
`nvm` No **Yes** No
`os` **Yes** **Yes** **Yes**
`pulseio` No **Yes** No
`pulseio` **Yes** **Yes** No
`random` **Yes** **Yes** **Yes**
`storage` **Yes** **Yes** **Yes**
`struct` **Yes** **Yes** **Yes**

View File

@ -52,7 +52,9 @@
//| :rtype: float
//|
STATIC mp_obj_t time_monotonic(void) {
return mp_obj_new_float(common_hal_time_monotonic() / 1000.0);
uint64_t time64 = common_hal_time_monotonic();
// 4294967296 = 2^32
return mp_obj_new_float(((uint32_t) (time64 >> 32) * 4294967296.0f + (uint32_t) (time64 & 0xffffffff)) / 1000.0f);
}
MP_DEFINE_CONST_FUN_OBJ_0(time_monotonic_obj, time_monotonic);