Merge pull request #15074 from maribu/ptp-clock

drivers/periph/ptp_clock
This commit is contained in:
benpicco 2020-12-03 09:59:07 +01:00 committed by GitHub
commit a80631a297
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
21 changed files with 1336 additions and 50 deletions

View File

@ -24,6 +24,9 @@ config BOARD_NUCLEO_F767ZI
select HAS_PERIPH_UART select HAS_PERIPH_UART
select HAS_PERIPH_USBDEV select HAS_PERIPH_USBDEV
select HAS_PERIPH_ETH select HAS_PERIPH_ETH
select HAS_PERIPH_PTP
select HAS_PERIPH_PTP_SPEED_ADJUSTMENT
select HAS_PERIPH_PTP_TIMER
# Put other features for this board (in alphabetical order) # Put other features for this board (in alphabetical order)
select HAS_RIOTBOOT select HAS_RIOTBOOT

View File

@ -3,14 +3,17 @@ CPU_MODEL = stm32f767zi
# Put defined MCU peripherals here (in alphabetical order) # Put defined MCU peripherals here (in alphabetical order)
FEATURES_PROVIDED += periph_dma FEATURES_PROVIDED += periph_dma
FEATURES_PROVIDED += periph_eth
FEATURES_PROVIDED += periph_i2c FEATURES_PROVIDED += periph_i2c
FEATURES_PROVIDED += periph_ptp
FEATURES_PROVIDED += periph_ptp_speed_adjustment
FEATURES_PROVIDED += periph_ptp_timer
FEATURES_PROVIDED += periph_rtc FEATURES_PROVIDED += periph_rtc
FEATURES_PROVIDED += periph_rtt FEATURES_PROVIDED += periph_rtt
FEATURES_PROVIDED += periph_spi FEATURES_PROVIDED += periph_spi
FEATURES_PROVIDED += periph_timer FEATURES_PROVIDED += periph_timer
FEATURES_PROVIDED += periph_uart FEATURES_PROVIDED += periph_uart
FEATURES_PROVIDED += periph_usbdev FEATURES_PROVIDED += periph_usbdev
FEATURES_PROVIDED += periph_eth
# Put other features for this board (in alphabetical order) # Put other features for this board (in alphabetical order)
FEATURES_PROVIDED += riotboot FEATURES_PROVIDED += riotboot

View File

@ -32,4 +32,8 @@ ifneq (,$(filter periph_can,$(FEATURES_USED)))
FEATURES_REQUIRED += periph_gpio_irq FEATURES_REQUIRED += periph_gpio_irq
endif endif
ifneq (,$(filter periph_eth periph_ptp,$(USEMODULE)))
USEMODULE += periph_eth_common
endif
include $(RIOTCPU)/cortexm_common/Makefile.dep include $(RIOTCPU)/cortexm_common/Makefile.dep

View File

@ -1154,6 +1154,23 @@ typedef struct eth_dma_desc {
#define TX_DESC_STAT_OWN (BIT31) /**< If set, descriptor is owned by DMA, otherwise by CPU */ #define TX_DESC_STAT_OWN (BIT31) /**< If set, descriptor is owned by DMA, otherwise by CPU */
/** @} */ /** @} */
#ifdef MODULE_PERIPH_ETH_COMMON
/**
* @brief Perform ETH initialization common to periph_stm32_eth and
* periph_ptp_clock
*/
void stm32_eth_common_init(void);
#endif /* MODULE_PERIPH_ETH_COMMON */
/**
* @name PTP clock configuration
* @{
*/
#define HAVE_PTP_CLOCK_READ 1 /**< Native implementation available */
#define HAVE_PTP_CLOCK_SET 1 /**< Native implementation available */
#define HAVE_PTP_TIMER_SET_ABSOLUTE 1 /**< Native implementation available */
/** @} */
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif

View File

@ -104,7 +104,7 @@ static edma_desc_t *tx_curr;
static char rx_buffer[ETH_RX_DESCRIPTOR_COUNT][ETH_RX_BUFFER_SIZE]; static char rx_buffer[ETH_RX_DESCRIPTOR_COUNT][ETH_RX_BUFFER_SIZE];
/* Netdev used in RIOT's API to upper layer */ /* Netdev used in RIOT's API to upper layer */
netdev_t *_netdev; netdev_t *stm32_eth_netdev;
#if IS_USED(MODULE_STM32_ETH_LINK_UP) #if IS_USED(MODULE_STM32_ETH_LINK_UP)
/* Used for checking the link status */ /* Used for checking the link status */
@ -403,37 +403,19 @@ static void _setup_phy(void)
static int stm32_eth_init(netdev_t *netdev) static int stm32_eth_init(netdev_t *netdev)
{ {
(void)netdev;
#if IS_USED(MODULE_STM32_ETH_LINK_UP) #if IS_USED(MODULE_STM32_ETH_LINK_UP)
_link_status_timer.callback = _timer_cb; _link_status_timer.callback = _timer_cb;
_link_status_timer.arg = netdev; _link_status_timer.arg = netdev;
xtimer_set(&_link_status_timer, STM32_ETH_LINK_UP_TIMEOUT_US); xtimer_set(&_link_status_timer, STM32_ETH_LINK_UP_TIMEOUT_US);
#endif #endif
/* enable APB2 clock */
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
/* select RMII if necessary */ /* The PTP clock is initialized prior to the netdevs and will have already
if (eth_config.mode == RMII) { * initialized the common stuff, if used.*/
SYSCFG->PMC |= SYSCFG_PMC_MII_RMII_SEL; if (!IS_USED(MODULE_PERIPH_INIT_PTP)) {
stm32_eth_common_init();
} }
/* initialize GPIO */
for (int i = 0; i < (int) eth_config.mode; i++) {
gpio_init(eth_config.pins[i], GPIO_OUT);
gpio_init_af(eth_config.pins[i], GPIO_AF11);
}
/* enable all clocks */
RCC->AHB1ENR |= (RCC_AHB1ENR_ETHMACEN | RCC_AHB1ENR_ETHMACTXEN |
RCC_AHB1ENR_ETHMACRXEN | RCC_AHB1ENR_ETHMACPTPEN);
/* reset the peripheral */
RCC->AHB1RSTR |= RCC_AHB1RSTR_ETHMACRST;
RCC->AHB1RSTR &= ~RCC_AHB1RSTR_ETHMACRST;
/* software reset */
ETH->DMABMR |= ETH_DMABMR_SR;
while (ETH->DMABMR & ETH_DMABMR_SR) {}
/* set the clock divider */ /* set the clock divider */
while (ETH->MACMIIAR & ETH_MACMIIAR_MB) {} while (ETH->MACMIIAR & ETH_MACMIIAR_MB) {}
ETH->MACMIIAR = CLOCK_RANGE; ETH->MACMIIAR = CLOCK_RANGE;
@ -465,7 +447,6 @@ static int stm32_eth_init(netdev_t *netdev)
_init_buffer(); _init_buffer();
NVIC_EnableIRQ(ETH_IRQn);
ETH->DMAIER |= ETH_DMAIER_NISE | ETH_DMAIER_TIE | ETH_DMAIER_RIE; ETH->DMAIER |= ETH_DMAIER_NISE | ETH_DMAIER_TIE | ETH_DMAIER_RIE;
/* enable transmitter and receiver */ /* enable transmitter and receiver */
@ -597,7 +578,7 @@ static void handle_lost_rx_irqs(void)
* risk a stack overflow if we would send an * risk a stack overflow if we would send an
* NETDEV_EVENT_RX_COMPLETE * NETDEV_EVENT_RX_COMPLETE
*/ */
netdev_trigger_event_isr(_netdev); netdev_trigger_event_isr(stm32_eth_netdev);
break; break;
} }
iter = iter->desc_next; iter = iter->desc_next;
@ -690,27 +671,6 @@ static void stm32_eth_isr(netdev_t *netdev)
netdev->event_callback(netdev, NETDEV_EVENT_RX_COMPLETE); netdev->event_callback(netdev, NETDEV_EVENT_RX_COMPLETE);
} }
void isr_eth(void)
{
unsigned tmp = ETH->DMASR;
if ((tmp & ETH_DMASR_TS)) {
ETH->DMASR = ETH_DMASR_NIS | ETH_DMASR_TS;
DEBUG("isr_eth: TX completed\n");
mutex_unlock(&stm32_eth_tx_completed);
}
if ((tmp & ETH_DMASR_RS)) {
ETH->DMASR = ETH_DMASR_NIS | ETH_DMASR_RS;
DEBUG("isr_eth: RX completed\n");
if (_netdev) {
netdev_trigger_event_isr(_netdev);
}
}
cortexm_isr_end();
}
static const netdev_driver_t netdev_driver_stm32f4eth = { static const netdev_driver_t netdev_driver_stm32f4eth = {
.send = stm32_eth_send, .send = stm32_eth_send,
.recv = stm32_eth_recv, .recv = stm32_eth_recv,
@ -722,6 +682,6 @@ static const netdev_driver_t netdev_driver_stm32f4eth = {
void stm32_eth_netdev_setup(netdev_t *netdev) void stm32_eth_netdev_setup(netdev_t *netdev)
{ {
_netdev = netdev; stm32_eth_netdev = netdev;
netdev->driver = &netdev_driver_stm32f4eth; netdev->driver = &netdev_driver_stm32f4eth;
} }

View File

@ -0,0 +1,102 @@
/*
* Copyright (C) 2016 TriaGnoSys GmbH
* 2020 Otto-von-Guericke-Universität Magdeburg
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu_stm32
* @{
*
* @file
* @brief Common code for the ETH and PTP driver
*
* @author Víctor Ariño <victor.arino@triagnosys.com>
* @author Marian Buschsieweke <marian.buschsieweke@ovgu.de>
*
* @}
*/
#include <string.h>
#include "mutex.h"
#include "net/netdev/eth.h"
#include "periph/gpio.h"
#include "periph/ptp.h"
#include "periph_conf.h"
#include "periph_cpu.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
void stm32_eth_common_init(void)
{
/* enable APB2 clock */
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
/* select RMII if necessary */
if (eth_config.mode == RMII) {
SYSCFG->PMC |= SYSCFG_PMC_MII_RMII_SEL;
}
/* initialize GPIO */
for (int i = 0; i < (int) eth_config.mode; i++) {
gpio_init(eth_config.pins[i], GPIO_OUT);
gpio_init_af(eth_config.pins[i], GPIO_AF11);
}
/* enable all clocks */
RCC->AHB1ENR |= (RCC_AHB1ENR_ETHMACEN | RCC_AHB1ENR_ETHMACTXEN |
RCC_AHB1ENR_ETHMACRXEN | RCC_AHB1ENR_ETHMACPTPEN);
/* reset the peripheral */
RCC->AHB1RSTR |= RCC_AHB1RSTR_ETHMACRST;
RCC->AHB1RSTR &= ~RCC_AHB1RSTR_ETHMACRST;
/* software reset */
ETH->DMABMR |= ETH_DMABMR_SR;
while (ETH->DMABMR & ETH_DMABMR_SR) {}
if (IS_USED(MODULE_PERIPH_ETH) || IS_USED(MODULE_PERIPH_PTP_TIMER)) {
NVIC_EnableIRQ(ETH_IRQn);
}
}
#if IS_USED(MODULE_STM32_ETH) || IS_USED(MODULE_PERIPH_PTP_TIMER)
void isr_eth(void)
{
DEBUG("[periph_eth_common] isr_eth()\n");
if (IS_USED(MODULE_PERIPH_PTP_TIMER)) {
if (ETH->MACSR & ETH_MACSR_TSTS) {
ptp_timer_cb();
/* clear interrupt by reading PTPTSSR */
(void)ETH->PTPTSSR;
}
}
if (IS_USED(MODULE_STM32_ETH)) {
extern netdev_t *stm32_eth_netdev;
extern mutex_t stm32_eth_tx_completed;
unsigned tmp = ETH->DMASR;
if ((tmp & ETH_DMASR_TS)) {
ETH->DMASR = ETH_DMASR_NIS | ETH_DMASR_TS;
DEBUG("isr_eth: TX completed\n");
mutex_unlock(&stm32_eth_tx_completed);
}
if ((tmp & ETH_DMASR_RS)) {
ETH->DMASR = ETH_DMASR_NIS | ETH_DMASR_RS;
DEBUG("isr_eth: RX completed\n");
if (stm32_eth_netdev) {
netdev_trigger_event_isr(stm32_eth_netdev);
}
}
}
cortexm_isr_end();
}
#endif

218
cpu/stm32/periph/ptp.c Normal file
View File

@ -0,0 +1,218 @@
/*
* Copyright (C) 2020 Otto-von-Guericke-Universität Magdeburg
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu_stm32
* @{
*
* @file
* @brief PTP clock and timer implementation
*
* @author Marian Buschsieweke <marian.buschsieweke@ovgu.de>
*
* @}
*/
#include <inttypes.h>
#include <string.h>
#include "assert.h"
#include "atomic_utils.h"
#include "bit.h"
#include "macros/units.h"
#include "periph/ptp.h"
#include "periph_conf.h"
#include "periph_cpu.h"
#include "timex.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/* Workaround for typos in vendor files; drop when fixed upstream */
#ifndef ETH_PTPTSCR_TSSSR
#define ETH_PTPTSCR_TSSSR ETH_PTPTSSR_TSSSR
#endif
#ifndef ETH_PTPTSCR_TSSARFE
#define ETH_PTPTSCR_TSSARFE ETH_PTPTSSR_TSSARFE
#endif
/* PTPSSIR is the number of nanoseconds to add onto the sub-second register
* (the one counting the nanoseconds part of the timestamp with the
* configuration we chose here). It is therefore the resolution of the clock
* in nanoseconds. (Note that the accuracy is expected to be way worse than
* the resolution.)
*/
#ifndef STM32_PTPSSIR
#if CLOCK_CORECLOCK > MHZ(200)
/* Go for 10 ns resolution on CPU clocked higher than 200 MHz */
#define STM32_PTPSSIR (10LLU)
#elif CLOCK_CORECLOCK > MHZ(100)
/* Go for 20 ns resolution on CPU clocked higher than 100 MHz */
#define STM32_PTPSSIR (20LLU)
#else
/* Go for 50 ns resolution on CPU all other CPUs */
#define STM32_PTPSSIR (50LLU)
#endif /* CLOCK_CORECLOCK */
#endif /* !STM32_PTPSSIR */
/**
* @brief Return the result of x / y, scientifically rounded
* @param x Number to divide
* @param y @p x should be divided by this
* @return x/y, scientifically rounded
* @pre Both @p x and @p y are compile time constant integers and the
* expressions are evaluated without side-effects
*/
#define ROUNDED_DIV(x, y) (((x) + ((y) / 2)) / (y))
static const uint32_t ptpssir = STM32_PTPSSIR;
static const uint32_t ptptsar = ROUNDED_DIV(NS_PER_SEC * (1ULL << 32), CLOCK_AHB * STM32_PTPSSIR);
void ptp_init(void)
{
/* The PTP clock is initialized during periph_init(), while stm32_eth is
* initialized during auto_init(). As auto_init() depends on periph_init(),
* we can be sure that the PTP clock is always the first to use the
* Ethernet MAC. The Ethernet driver will skip the common initialization
* part when the PTP clock is used. */
stm32_eth_common_init();
/* In the following, the steps described in "Programming steps for
* system time generation initialization" on page 1805 in RM0410 Rev4
* are done */
/* Mask the time stamp trigger interrupt */
ETH->MACIMR |= ETH_MACIMR_TSTIM;
/* Set TSE bit in time stamp register to enable time stamping */
ETH->PTPTSCR |= ETH_PTPTSCR_TSE;
/* Use decimal mode (subsecond register counts nanoseconds, not in
* 2^(-31) seconds) */
ETH->PTPTSCR |= ETH_PTPTSCR_TSSSR;
/* Set subsecond increment register. This will be added onto the subsecond
* register whenever a 32 bit accumulator register overflows*/
ETH->PTPSSIR = ptpssir;
ptp_clock_adjust_speed(0);
/* Wait new PTPSAR value becomes active */
while (ETH->PTPTSCR & ETH_PTPTSCR_TSARU) { }
/* Enable fine grained correction now */
ETH->PTPTSCR |= ETH_PTPTSCR_TSFCU;
static const ptp_timestamp_t initial_time = {
.seconds = 0,
.nanoseconds = 0
};
ptp_clock_set(&initial_time);
if (IS_USED(MODULE_PERIPH_ETH)) {
/* enable timestamping of all received frames */
ETH->PTPTSCR |= ETH_PTPTSSR_TSSARFE;
}
DEBUG("[periph_ptp] Initialized with PTPSAR = %" PRIu32 ", PTPSSIR = %" PRIu32 "\n",
ptptsar, ptpssir);
}
void ptp_clock_adjust_speed(int16_t correction)
{
uint64_t offset = ptptsar;
offset *= correction;
offset >>= 16;
uint32_t adjusted_ptptsar = ptptsar + (uint32_t)offset;
/* Value to add onto the 32 bit accumulator register (which causes the
* value in ETH->PTPSSIR to be added onto the subsection register on
* overflow) */
ETH->PTPTSAR = adjusted_ptptsar;
/* Wait for pending clock speed adjustments to complete */
while (ETH->PTPTSCR & ETH_PTPTSCR_TSARU) { }
/* Load new PTPTSAR value to hardware */
ETH->PTPTSCR |= ETH_PTPTSCR_TSARU;
DEBUG("[periph_ptp] Using PTPSAR = %" PRIu32 ", PTPSSIR = %" PRIu32 "\n",
adjusted_ptptsar, ptpssir);
}
void ptp_clock_adjust(int64_t offset)
{
unsigned state = irq_disable();
ptp_timestamp_t ts;
uint64_t abs_offset = (offset < 0) ? -offset : offset;
ptp_ns2ts(&ts, abs_offset);
ETH->PTPTSHUR = ts.seconds;
ETH->PTPTSLUR = (offset < 0) ? (1UL << 31) | ts.nanoseconds : ts.nanoseconds;
while (ETH->PTPTSCR & (ETH_PTPTSCR_TSSTU | ETH_PTPTSCR_TSSTI)) {
/* wait until new time value can be set */
}
ETH->PTPTSCR |= ETH_PTPTSCR_TSSTU;
irq_restore(state);
DEBUG("[periph_ptp] Updated time by %c%" PRIu32 ".%09" PRIu32 "\n",
(offset < 0) ? '-' : '+', (uint32_t)ts.seconds, ts.nanoseconds);
}
void ptp_clock_set(const ptp_timestamp_t *time)
{
assert(time && time->nanoseconds < NS_PER_SEC);
unsigned state = irq_disable();
/* First, set the timestamp update registers */
ETH->PTPTSHUR = time->seconds;
ETH->PTPTSLUR = time->nanoseconds;
/* From the data sheet (regarding setting TSSTI):
* > Both the TSSTU and TSSTI bits must be read as zero before you can set
* > this bit.
*/
while (ETH->PTPTSCR & (ETH_PTPTSCR_TSSTU | ETH_PTPTSCR_TSSTI)) {
/* wait until new time value can be set */
}
/* Now, ask the peripheral to atomically set the clock from the update
* registers */
ETH->PTPTSCR |= ETH_PTPTSCR_TSSTI;
irq_restore(state);
}
void ptp_clock_read(ptp_timestamp_t *timestamp)
{
unsigned irq_state = irq_disable();
/* Read first high register, then low, then again high. If the value in
* high register changed between the reads, we start again to prevent
* corrupted timestamps being passed to the user. */
do {
timestamp->seconds = ETH->PTPTSHR;
timestamp->nanoseconds = ETH->PTPTSLR;
} while (timestamp->seconds != ETH->PTPTSHR);
/* TODO: Most significant bit of ETH->PTPTSLR is the sign bit of the time
* stamp. Because the seconds register is unsigned, an overflow is not
* expected before year 2106. It is not clear from the data sheet, how the
* time stamp is to be interpreted when the negative bit is set. For now,
* we just ignore this potential source of problems. */
irq_restore(irq_state);
}
#if IS_USED(MODULE_PERIPH_PTP_TIMER)
void ptp_timer_clear(void)
{
const atomic_bit_u32_t tsite = atomic_bit_u32(&ETH->PTPTSCR, ETH_PTPTSCR_TSITE_Pos);
atomic_clear_bit_u32(tsite);
}
void ptp_timer_set_absolute(const ptp_timestamp_t *target)
{
assert(target);
DEBUG("[periph_ptp] Set timer: %" PRIu32 ".%" PRIu32 "\n",
(uint32_t)target->seconds, target->nanoseconds);
unsigned state = irq_disable();
/* Mask PTP timer IRQ first, so that an interrupt is not triggered
* too early. (The target time is not set atomically.) */
ETH->MACIMR |= ETH_MACIMR_TSTIM;
/* Set target time */
ETH->PTPTTHR = target->seconds;
ETH->PTPTTLR = target->nanoseconds;
/* Enable PTP timer IRQ */
ETH->PTPTSCR |= ETH_PTPTSCR_TSITE;
/* Unmask the time stamp trigger interrupt */
ETH->MACIMR &= ~ETH_MACIMR_TSTIM;
irq_restore(state);
DEBUG("PTPTSCR: 0x%08x, MACIMR: 0x%08x, MACSR: 0x%08x\n",
(unsigned)ETH->PTPTSCR, (unsigned)ETH->MACIMR, (unsigned)ETH->MACSR);
}
#endif /* IS_USED(MODULE_PTP_TIMER) */

View File

@ -102,6 +102,10 @@ ifneq (,$(filter nrfmin,$(USEMODULE)))
USEMODULE += netif USEMODULE += netif
endif endif
ifneq (,$(filter periph_ptp_timer periph_ptp_speed_adjustment,$(FEATURES_USED)))
FEATURES_REQUIRED += periph_ptp
endif
ifneq (,$(filter qmc5883l_%,$(USEMODULE))) ifneq (,$(filter qmc5883l_%,$(USEMODULE)))
USEMODULE += qmc5883l USEMODULE += qmc5883l
endif endif

View File

@ -0,0 +1,408 @@
/*
* Copyright (C) 2020 Otto-von-Guericke-Universität Magdeburg
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @defgroup drivers_periph_ptp PTP-Clock
* @ingroup drivers_periph
* @brief Low-level PTP clock peripheral driver
*
* # Introduction
*
* The [Precision Time Protocol (PTP)](https://standards.ieee.org/content/ieee-standards/en/standard/1588-2019.html)
* can be used to synchronize clocks with hardware support in an Ethernet PHY,
* that allows to precisely estimate (and, thus, compensate) network delay
* between time server and client. This allows PTP synchronization to be highly
* accurate (<< 1 µs offset between server and client), but requires hardware
* support on each synchronized node and the PTP server, all nodes to be
* connected to the same* Ethernet network, and (for best results) hardware
* support in all intermediate switches.
*
* # (No) Synchronization Using This API
*
* This API is intended to provide basic access to a PTP hardware clock. This
* does not cover any synchronization. Some PTP hardware clocks (e.g. on the
* STM32) can be used without synchronization by manually setting the time.
* Thus, the PTP clock can be useful even without synchronization implemented.
*
* It is intended that the actual synchronization is implemented externally
* later on. The functions @ref ptp_clock_adjust and @ref ptp_clock_adjust_speed
* are specified with the needs of a synchronization solution in mind.
*
* # Clock vs Timer
*
* This API provides both `ptp_clock_*()` and `ptp_timer_*()` functions, to
* distinguish between the feature set being used. A PTP peripheral might only
* support the feature `periph_ptp`, but not `periph_ptp_timer`.
*
* # (Lack of) Power Considerations
*
* It is assumed that a board connected to a wired network is also powered
* from mains. Additionally, a high-resolution high-accuracy clock that is
* periodically synced over network is just not going to play well with
* low-power application scenarios.
*
* @{
* @file
* @brief Low-level PTP clock peripheral driver interface definitions
*
* @author Marian Buschsieweke <marian.buschsieweke@ovgu.de>
*/
#ifndef PERIPH_PTP_H
#define PERIPH_PTP_H
#include <stdint.h>
#include "periph_cpu.h"
#include "timex.h"
#ifdef __cplusplus
extern "C" {
#endif
/* verify settings from periph_cpu.h */
#if !defined(HAVE_PTP_CLOCK_READ) && !defined(HAVE_PTP_CLOCK_READ_U64)
#error "Neither ptp_clock_read() nor ptp_clock_read_u64() implemented"
#endif
#if !defined(HAVE_PTP_CLOCK_SET) && !defined(HAVE_PTP_CLOCK_SET_U64)
#error "Neither ptp_clock_set() nor ptp_clock_set_u64() implemented"
#endif
#if \
!defined(HAVE_PTP_TIMER_SET_ABSOLUTE) && \
!defined(HAVE_PTP_TIMER_SET_ABSOLUTE_U64) && \
IS_USED(MODULE_PERIPH_PTP_TIMER)
#error "Neither ptp_timer_set_absolute() nor ptp_timer_set_absolute_u64() implemented"
#endif
/**
* @brief Unsigned integer type to store seconds since epoch for use in PTP
*
* The PTP protocol defines the seconds part of PTP timestamps as an 48 bit
* unsigned integer. We go for 32 bit for now (works until year 2106) and will
* later extend this type to 64 bit. Users are highly encouraged to use this
* type instead of `uint32_t`, if they intent that their software still works
* in a couple of decades.
*/
typedef uint32_t ptp_seconds_t;
/**
* @brief A PTP timestamp in seconds + nanoseconds since UNIX epoch
*
* According to IEEE 1588-2019 specification in section "5.3.3 Timestamp",
* timestamps are represented as seconds and nanoseconds since epoch. For the
* seconds parts an 48 bit unsigned integer is used in the protocol and a 32 bit
* unsigned integer for the nanoseconds.
*/
typedef struct {
ptp_seconds_t seconds; /**< Seconds since UNIX epoch */
uint32_t nanoseconds; /**< Nanoseconds part */
} ptp_timestamp_t;
/**
* @brief Compare two PTP timestamps
*
* @param a First timestamp
* @param b Second timestamp
*
* @retval -1 @p a < @p b
* @retval 0 @p a == @p b
* @retval 1 @p a > @p b
*/
static inline int ptp_cmp(const ptp_timestamp_t *a, const ptp_timestamp_t *b)
{
if (a->seconds < b->seconds) {
return -1;
}
if (a->seconds > b->seconds) {
return 1;
}
if (a->nanoseconds < b->nanoseconds) {
return -1;
}
if (a->nanoseconds > b->nanoseconds) {
return 1;
}
return 0;
}
/**
* @brief Add a given offset onto the given timestamp
*
* @param[in,out] t Timestamp to add offset to
* @param[in] offset Offset to apply
*/
static inline void ptp_add(ptp_timestamp_t *t, int64_t offset)
{
/* Modulo for negative numbers should be avoided */
if (offset >= 0) {
uint64_t abs_offset = offset;
t->seconds += abs_offset / NS_PER_SEC;
t->nanoseconds += abs_offset % NS_PER_SEC;
/* correct overflow of nanosecond part */
if (t->nanoseconds >= NS_PER_SEC) {
t->nanoseconds -= NS_PER_SEC;
t->seconds++;
}
}
else {
uint64_t abs_offset = -offset;
t->seconds -= abs_offset / NS_PER_SEC;
t->nanoseconds -= abs_offset % NS_PER_SEC;
/* correct underflow of nanosecond part */
if (t->nanoseconds > NS_PER_SEC) {
t->nanoseconds += NS_PER_SEC;
t->seconds--;
}
}
}
/**
* @brief Convert time from nanoseconds since epoch to ptp_timestamp_t format
*
* @param[out] dest The timestamp will be written here
* @param[in] ns_since_epoch Time in nanoseconds since epoch to convert
*/
static inline void ptp_ns2ts(ptp_timestamp_t *dest, uint64_t ns_since_epoch)
{
dest->seconds = ns_since_epoch / NS_PER_SEC;
dest->nanoseconds = ns_since_epoch % NS_PER_SEC;
}
/**
* @brief Convert time from nanoseconds since epoch to ptp_timestamp_t format
*
* @param[in] t Time to convert to nanoseconds since epoch
*
* @return The time specified by @p t in nanoseconds since epoch
*/
static inline uint64_t ptp_ts2ns(const ptp_timestamp_t *t)
{
return t->seconds * NS_PER_SEC + t->nanoseconds;
}
/**
* @brief Initialize the given PTP peripheral
*
* @note Implementations of this functions have to use `assert()` to make
* the configuration is valid.
*
* @pre This function must be called at most once
*
* After calling this, the PTP clock (and the PTP timer, if the feature
* `periph_ptp_timer` is used in addition to `periph_ptp_clock`) can be used.
*/
void ptp_init(void);
/**
* @brief Adjust the PTP clock speed as given
*
* @param correction Specification of the clock speed adjustment
*
* @note This implies feature `periph_ptp_speed_adjustment`
*
* The clock speed is adjusted in regard to its nominal clock speed. This means
* that calls with the same value in @p correction are idempotent.
*
* 1. A call with @p correction set to `0` restores the nominal clock speed.
* 2. A call with a positive value for @p correction speeds the clock up
* by `correction / (1 << 16)` (so up to ~50% for `INT16_MAX`).
* 3. A call with a negative value for @p correction slows the clock down by
* `-correction / (1 << 16)` (so up to 50% for `INT16_MIN`).
*
* This allows the clock speed to be adjusted in steps ± 0.00153% in relation
* to its nominal clock speed, thus, allowing to counter systematic clock drift.
* In addition, this is intended to "smoothly" synchronize the clock over time
* to avoid jumps in the system time. (Especially calling @ref ptp_clock_adjust
* with negative values might be something to avoid, when applications are not
* prepared with clocks going backwards.)
*/
void ptp_clock_adjust_speed(int16_t correction);
/**
* @brief Adjust the PTP clock as given
*
* @param offset Offset to add onto current system time
*
* Same as `ptp_clock_set_u64(ptp_clock_read_u64() + offset)`, but implemented
* to introduce as little error as possible while setting the offset. This
* is intended to be used by clock synchronization implementations.
*/
void ptp_clock_adjust(int64_t offset);
#if defined(HAVE_PTP_CLOCK_READ) || defined(DOXYGEN)
/**
* @brief Get the current system time as PTP timestamp
*
* @param[out] timestamp The timestamp will be written here
* @pre The PTP clock is initialized
*/
void ptp_clock_read(ptp_timestamp_t *timestamp);
#endif /* HAVE_PTP_CLOCK_READ */
#if defined(HAVE_PTP_CLOCK_READ_U64) || defined(DOXYGEN)
/**
* @brief Get the current system time in nanosecond since UNIX epoch
*
* @return Nanoseconds since 1. 1. 1970 0:00:00 UTC
*
* @pre The PTP clock is initialized
*
* @note An `uint64_t` allows nanosecond timestamps within 1970-01-01 and
* 2554-07-21 to be represented.
*/
uint64_t ptp_clock_read_u64(void);
#endif /* HAVE_PTP_CLOCK_READ_U64 */
#if defined(HAVE_PTP_CLOCK_SET) || defined(DOXYGEN)
/**
* @brief Set the current system time
*
* @param time The new system time
*
* @pre The PTP clock is initialized
*/
void ptp_clock_set(const ptp_timestamp_t *time);
#endif /* HAVE_PTP_CLOCK_SET */
#if defined(HAVE_PTP_CLOCK_SET_U64) || defined(DOXYGEN)
/**
* @brief Set the current system time in nanosecond since UNIX epoch
*
* @param ns_since_epoch New time to set
*
* @pre The PTP clock is initialized
*/
void ptp_clock_set_u64(uint64_t ns_since_epoch);
#endif /* HAVE_PTP_CLOCK_SET_U64 */
/**
* @brief External function to call when the PTP clock timer fired
*
* @note This function needs to be implemented by the *user* of this API
* @note This function implies feature `periph_ptp_timer`
*
* Since at most one PTP clock is expected on each board, we can avoid the
* overhead of indirect function calls here and let users of this API just
* implement this function.
*/
void ptp_timer_cb(void);
#if defined(HAVE_PTP_TIMER_SET_ABSOLUTE) || defined(DOXYGEN)
/**
* @brief Set an absolute timeout value, possibly overwriting an existing
* timeout
*
* @param target Timestamp when the timeout should fire
*
* @note Only a single timeout is supported by the PTP timer
* @note This function implies feature `periph_ptp_timer`
*
* @details If the target time is in the past or equal to the current time, the
* IRQ should trigger right away.
*/
void ptp_timer_set_absolute(const ptp_timestamp_t *target);
#endif /* HAVE_PTP_TIMER_SET_ABSOLUTE */
#if defined(HAVE_PTP_TIMER_SET_ABSOLUTE_U64) || defined(DOXYGEN)
/**
* @brief Set an absolute timeout value, possibly overwriting an existing
* timeout
*
* @param target Timestamp when the timeout should fire (ns since epoch)
*
* @note Only a single timeout is supported by the PTP timer
* @note This function implies feature `periph_ptp_timer`
*
* @details If the target time is in the past or equal to the current time, the
* IRQ should trigger right away.
*/
void ptp_timer_set_absolute_u64(uint64_t target);
#endif /* HAVE_PTP_TIMER_SET_ABSOLUTE_U64 */
/**
* @brief Set an relative timeout value, possibly overwriting an existing
* timeout
*
* @param target Number of nanoseconds after which the timeout should fire
*
* @note Only a single timeout is supported by the PTP timer
* @note This function implies feature `periph_ptp_timer`
*/
void ptp_timer_set_u64(uint64_t target);
/**
* @brief Clears any pending timeout on the PTP timer
*
* @note This function implies feature `periph_ptp_timer`
*/
void ptp_timer_clear(void);
/* Fallback implementations (the driver can implement either the
* functions using `ptp_timestamp_t` or `uint64_t`, the other flavor will
* be provided on top here): */
#ifndef HAVE_PTP_CLOCK_READ
static inline void ptp_clock_read(struct ptp_timestamp_t *timestamp)
{
ptp_ns2ts(timestamp, ptp_clock_read_u64());
}
#endif /* !HAVE_PTP_CLOCK_READ */
#ifndef HAVE_PTP_CLOCK_READ_U64
static inline uint64_t ptp_clock_read_u64(void)
{
ptp_timestamp_t ts;
ptp_clock_read(&ts);
return ptp_ts2ns(&ts);
}
#endif /* !HAVE_PTP_CLOCK_READ_U64 */
#ifndef HAVE_PTP_CLOCK_SET
static inline void ptp_clock_set(const ptp_timestamp_t *time)
{
ptp_clock_set_u64(ptp_ts2ns(time));
}
#endif /* !HAVE_PTP_CLOCK_SET */
#ifndef HAVE_PTP_CLOCK_SET_U64
static inline void ptp_clock_set_u64(uint64_t ns_since_epoch)
{
ptp_timestamp_t time;
ptp_ns2ts(&time, ns_since_epoch);
ptp_clock_set(&time);
}
#endif /* !HAVE_PTP_CLOCK_SET_U64 */
#ifndef HAVE_PTP_TIMER_SET_ABSOLUTE
static inline void ptp_timer_set_absolute(const ptp_timestamp_t *target)
{
ptp_timer_set_absolute_u64(ptp_ts2ns(target));
}
#endif /* !HAVE_PTP_TIMER_SET_ABSOLUTE */
#ifndef HAVE_PTP_TIMER_SET_ABSOLUTE_U64
static inline void ptp_timer_set_absolute_u64(uint64_t target)
{
ptp_timestamp_t ts;
ptp_ns2ts(&ts, target);
ptp_timer_set_absolute(&ts);
}
#endif /* !HAVE_PTP_TIMER_SET_ABSOLUTE_U64 */
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_PTP_H */
/** @} */

View File

@ -46,6 +46,9 @@
#ifdef MODULE_PERIPH_INIT_WDT #ifdef MODULE_PERIPH_INIT_WDT
#include "periph/wdt.h" #include "periph/wdt.h"
#endif #endif
#ifdef MODULE_PERIPH_INIT_PTP
#include "periph/ptp.h"
#endif
#endif /* MODULE_PERIPH_INIT */ #endif /* MODULE_PERIPH_INIT */
void periph_init(void) void periph_init(void)
@ -92,5 +95,9 @@ void periph_init(void)
wdt_init(); wdt_init();
#endif #endif
#if defined(MODULE_PERIPH_INIT_PTP)
ptp_init();
#endif
#endif /* MODULE_PERIPH_INIT */ #endif /* MODULE_PERIPH_INIT */
} }

View File

@ -0,0 +1,50 @@
/*
* Copyright (C) 2020 Otto-von-Guericke-Universität Magdeburg
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup drivers_periph_ptp
* @{
*
* @file
* @brief Common code for PTP clocks and timers
*
* @author Marian Buschsieweke <marian.buschsieweke@ovgu.de>
*
* @}
*/
#include "kernel_defines.h"
#if IS_USED(MODULE_PERIPH_PTP_TIMER)
#include "irq.h"
#include "periph/ptp.h"
#if !defined(HAVE_PTP_TIMER_SET_U64)
void ptp_timer_set_u64(uint64_t target)
{
unsigned irq_state = irq_disable();
if (IS_ACTIVE(HAVE_PTP_TIMER_SET_ABSOLUTE) && IS_ACTIVE(HAVE_PTP_CLOCK_READ)) {
/* This is slightly more efficient when the PTP clock implementation
* uses ptp_timestamp_t natively */
ptp_timestamp_t now;
ptp_clock_read(&now);
now.seconds += target / NS_PER_SEC;
now.nanoseconds += target % NS_PER_SEC;
while (now.nanoseconds >= NS_PER_SEC) {
now.seconds++;
now.nanoseconds -= NS_PER_SEC;
}
ptp_timer_set_absolute(&now);
}
else {
ptp_timer_set_absolute_u64(ptp_clock_read_u64() + target);
}
irq_restore(irq_state);
}
#endif /* !defined(HAVE_PTP_TIMER_SET_U64) */
#else
typedef int dont_be_pedantic;
#endif

View File

@ -205,6 +205,21 @@ config HAS_PERIPH_PM
help help
Indicates that a Power Management (PM) peripheral is present. Indicates that a Power Management (PM) peripheral is present.
config HAS_PERIPH_PTP
bool
help
Indicates that a PTP clock is present.
config HAS_PERIPH_PTP_SPEED_ADJUSTMENT
bool
help
Indicates that the PTP clock speed can be adjust. This can be used for clock drift correction and synchronization.
config HAS_PERIPH_PTP_TIMER
bool
help
Indicates that the PTP clock can be used as timer.
config HAS_PERIPH_PWM config HAS_PERIPH_PWM
bool bool
help help

View File

@ -66,7 +66,7 @@ extern "C" {
/** /**
* @brief The number of nanoseconds per second * @brief The number of nanoseconds per second
*/ */
#define NS_PER_SEC (1000000000U) #define NS_PER_SEC (1000000000LLU)
/** /**
* @brief The maximum length of the string representation of a timex timestamp * @brief The maximum length of the string representation of a timex timestamp

View File

@ -0,0 +1,16 @@
BOARD ?= nucleo-f767zi
include ../Makefile.tests_common
FEATURES_REQUIRED += periph_ptp
FEATURES_OPTIONAL += periph_ptp_speed_adjustment
FEATURES_REQUIRED += periph_timer_periodic
USEMODULE += fmt
TIMER_FREQ ?=
include $(RIOTBASE)/Makefile.include
ifneq (,$(TIMER_FREQ))
CFLAGS += -DTIM_FREQ=$(TIMER_FREQ)
endif

View File

@ -0,0 +1,67 @@
Peripheral PTP Clock Test Application
=====================================
Hardware Requirements
---------------------
In addition to the `periph_ptp` feature, this tests requires the peripheral
timer to be run on a clock synchronous to the PTP clock. Otherwise clock
drift between the two clocks might result in the test failing even though the
driver works correctly.
Verifying Clock Speed Adjustment
--------------------------------
In the first part of the test the speed of the PTP clock is adjusted to
different values. The test sleeps for 0.5 seconds and verifies that the clock
drift between the high level timer API and PTP clock matches the speed
adjustment (± 0.01%).
Verifying Clock Adjustment
--------------------------
The second part of the test verifies that adjusting the clock does not
introduce noticeable errors. The clock speed is set back to nominal speed
prior to this test part (so that it synchronous to the high level timer). For
each of a set of predefined clock adjustment values the following is done:
- `xtimer_period_wakeup()` is used to get 50 wake ups after 10 ms each
- right before sleeping, the PTP clock is adjusted
- right after the wake up, the PTP clock is read
- The difference between the two PTP timestamps should be the sum of the
10 ms period length and the adjustment
- The difference of the actual result and the expected result
(10 ms + adjustment) is stored for each round
- The average, minimum, maximum, and variance (σ²) is calculated from these
differences between actual period length and expected period length
A test run is considered a pass, if the average error is less than ± 250 ns
and minimum/maximum error are less than ± 500 ns.
Expected Output on Success
--------------------------
main(): This is RIOT! (Version: <INSERT VERSION HERE>)
Testing clock at speed 0 (~100.000 % of nominal speed): SUCCEEDED
Testing clock at speed 32767 (~149.999 % of nominal speed): SUCCEEDED
Testing clock at speed -32768 (~50.000 % of nominal speed): SUCCEEDED
Testing clock at speed 1337 (~102.040 % of nominal speed): SUCCEEDED
Testing clock at speed -1337 (~97.961 % of nominal speed): SUCCEEDED
Testing clock at speed 42 (~100.064 % of nominal speed): SUCCEEDED
Testing clock at speed -42 (~99.937 % of nominal speed): SUCCEEDED
Testing clock at speed 665 (~101.015 % of nominal speed): SUCCEEDED
Testing clock at speed -665 (~98.986 % of nominal speed): SUCCEEDED
Testing clock adjustments for offset 0: SUCCEEDED
Statistics: avg = 0, min = 0, max = 0, σ² = 0
Testing clock adjustments for offset -1337: SUCCEEDED
Statistics: avg = 0, min = 0, max = 0, σ² = 0
Testing clock adjustments for offset 1337: SUCCEEDED
Statistics: avg = 0, min = 0, max = 0, σ² = 0
Testing clock adjustments for offset 2147483647: SUCCEEDED
Statistics: avg = 0, min = 0, max = 0, σ² = 0
TEST SUCCEEDED!
Note: If the values in the statistics of the clock adjustments differ to some
degree, this might be due ISR overhead and jitter when reading the
PTP timer from the periodic peripheral timer callback. The test will only
fail if either the worst case offset or the variance are too big.

View File

@ -0,0 +1,261 @@
/*
* Copyright (C) 2020 Otto-von-Guericke-Universität Magdeburg
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup tests
* @{
*
* @file
* @brief Peripheral PTP clock test application
*
* @author Marian Buschsieweke <marian.buschsieweke@ovgu.de>
*
* @}
*/
#include <stdint.h>
#include <stdatomic.h>
#include <stdlib.h>
#include "fmt.h"
#include "kernel_defines.h"
#include "macros/units.h"
#include "mutex.h"
#include "periph/ptp.h"
#include "periph/timer.h"
#define TEST_TIME_US (US_PER_SEC / 2)
#define TEST_ROUNDS (50)
#define PERIOD_US (TEST_TIME_US / TEST_ROUNDS)
#ifndef TIM
#define TIM TIMER_DEV(0)
#endif
#ifndef TIM_FREQ
#define TIM_FREQ MHZ(1)
#endif
#define TIM_PERIOD (1ULL * PERIOD_US * TIM_FREQ / US_PER_SEC - 1)
#define TIM_TIME (1ULL * TEST_TIME_US * TIM_FREQ / US_PER_SEC)
static mutex_t sync_mutex = MUTEX_INIT_LOCKED;
static atomic_uint_least64_t timestamp;
static inline void print_s64_dec(int64_t _num)
{
uint64_t num = _num;
if (_num < 0) {
print_str("-");
num = -_num;
}
print_u64_dec(num);
}
static void speed_adj_cb(void *arg, int chan)
{
(void)arg;
(void)chan;
mutex_unlock(&sync_mutex);
}
static int test_speed_adjustment(const int16_t speed)
{
uint32_t expected_ns = TEST_TIME_US * 1000;
expected_ns += ((int64_t)expected_ns * speed) >> 16;
const uint32_t expected_ns_lower = expected_ns * 9999ULL / 10000ULL;
const uint32_t expected_ns_upper = expected_ns * 10001ULL / 10000ULL;
ptp_clock_adjust_speed(speed);
print_str("Testing clock at speed ");
print_s32_dec(speed);
print_str(" (~");
{
int64_t tmp = speed * 100000ULL;
tmp = (tmp + UINT16_MAX / 2) / UINT16_MAX;
tmp += 100000ULL;
char output[16];
print(output, fmt_s32_dfp(output, (int32_t)tmp, -3));
}
print_str(" % of nominal speed): ");
if (timer_init(TIM, TIM_FREQ, speed_adj_cb, NULL)) {
print_str("FAILED.\nCouldn't set up periph_timer for comparison\n");
return 1;
}
/* be double sure mutex is indeed locked */
mutex_trylock(&sync_mutex);
timer_stop(TIM);
if (timer_set(TIM, 0, TIM_TIME)) {
print_str("FAILED.\nCouldn't set periph_timer for comparison\n");
return 1;
}
uint64_t start_ns = ptp_clock_read_u64();
timer_start(TIM);
mutex_lock(&sync_mutex);
uint64_t got_ns = ptp_clock_read_u64() - start_ns;
timer_stop(TIM);
uint64_t diff_ns = 0;
int failed = 0;
if (got_ns > expected_ns_upper) {
failed = 1;
diff_ns = got_ns - expected_ns;
}
else if (got_ns < expected_ns_lower) {
failed = 1;
diff_ns = expected_ns - got_ns;
}
if (failed) {
int64_t tmp = (int64_t)got_ns - (int64_t)expected_ns;
tmp = (tmp * 100000LL + expected_ns / 2) / expected_ns;
tmp += 100000LL;
char percentage[16];
print_str("FAILED\n");
print_str("expected: ");
print_u64_dec(expected_ns);
print_str(", got: ");
print_u64_dec(got_ns);
print_str(", diff: ");
print_u64_dec(diff_ns);
print_str(" (");
print(percentage, fmt_s32_dfp(percentage, (int32_t)tmp, -3));
print_str("% offset)\n");
}
else {
print_str("SUCCEEDED\n");
}
return failed;
}
static void clock_adj_cb(void *arg, int chan)
{
int32_t offset = (uintptr_t)arg;
(void)chan;
uint64_t now = ptp_clock_read_u64();
ptp_clock_adjust(offset);
atomic_store(&timestamp, now);
mutex_unlock(&sync_mutex);
}
static int test_clock_adjustment(int32_t offset)
{
/* Record one extra sample, to throw away the first measurement */
static int64_t diffs[TEST_ROUNDS + 1];
int64_t period_ns = PERIOD_US * 1000ULL + offset;
uint64_t last_ns;
print_str("Testing clock adjustments for offset ");
print_s32_dec(offset);
print_str(": ");
/* be double sure mutex is indeed locked */
mutex_trylock(&sync_mutex);
if (timer_init(TIM, TIM_FREQ, clock_adj_cb, (void *)offset) ||
timer_set_periodic(TIM, 0, TIM_PERIOD, TIM_FLAG_RESET_ON_MATCH)) {
print_str("FAILED.\nCouldn't set up periph_timer for comparison\n");
return 1;
}
/* wait for periodic timer IRQ */
mutex_lock(&sync_mutex);
last_ns = atomic_load(&timestamp);
for (unsigned i = 0; i < TEST_ROUNDS + 1; i++) {
/* wait for periodic timer IRQ */
mutex_lock(&sync_mutex);
uint64_t now_ns = atomic_load(&timestamp);
diffs[i] = (int64_t)(now_ns - last_ns) - period_ns;
last_ns = now_ns;
}
timer_stop(TIM);
int64_t avg = 0, var = 0, min = INT64_MAX, max = INT64_MIN;
for (unsigned i = 1; i < TEST_ROUNDS + 1; i++) {
avg += diffs[i];
}
avg = (avg + TEST_ROUNDS / 2) / TEST_ROUNDS;
for (unsigned i = 1; i < TEST_ROUNDS + 1; i++) {
int64_t tmp = diffs[i] - avg;
var += tmp * tmp;
if (diffs[i] < min) {
min = diffs[i];
}
if (diffs[i] > max) {
max = diffs[i];
}
}
var = (var + TEST_ROUNDS / 2) / TEST_ROUNDS;
int failed = 0;
if ((max < 500) && (min > -500) && (avg < 250) && (avg > -250)) {
print_str("SUCCEEDED\n");
}
else {
failed = 1;
print_str("FAILED\nDiffs:\n");
for (unsigned i = 1; i < TEST_ROUNDS + 1; i++) {
print_s64_dec(diffs[i]);
print_str("\n");
}
}
print_str("Statistics: avg = ");
print_s64_dec(avg);
print_str(", min = ");
print_s64_dec(min);
print_str(", max = ");
print_s64_dec(max);
print_str(", σ² = ");
print_s64_dec(var);
print_str("\n");
return failed;
}
int main(void)
{
static const int16_t speeds[] = {
0, INT16_MAX, INT16_MIN, 1337, -1337, 42, -42, 665, -665
};
static const int32_t offsets[] = {
0, -1337, +1337, INT32_MAX
};
int failed = 0;
if (IS_USED(MODULE_PERIPH_PTP_SPEED_ADJUSTMENT)) {
for (size_t i = 0; i < ARRAY_SIZE(speeds); i++) {
failed |= test_speed_adjustment(speeds[i]);
}
/* Restore nominal clock speed */
ptp_clock_adjust_speed(0);
}
for (size_t i = 0; i < ARRAY_SIZE(offsets); i++) {
failed |= test_clock_adjustment(offsets[i]);
}
if (failed) {
print_str("TEST FAILED!\n");
}
else {
print_str("TEST SUCCEEDED!\n");
}
return 0;
}

View File

@ -0,0 +1,18 @@
#!/usr/bin/env python3
# Copyright (C) 2020 Otto-von-Guericke-Universität Magdeburg
#
# This file is subject to the terms and conditions of the GNU Lesser
# General Public License v2.1. See the file LICENSE in the top level
# directory for more details.
import sys
from testrunner import run
def testfunc(child):
child.expect_exact("TEST SUCCEEDED!\r\n")
if __name__ == "__main__":
sys.exit(run(testfunc))

View File

@ -0,0 +1,9 @@
BOARD ?= nucleo-f767zi
include ../Makefile.tests_common
FEATURES_REQUIRED = periph_ptp_timer
USEMODULE += event
USEMODULE += fmt
include $(RIOTBASE)/Makefile.include

View File

@ -0,0 +1,17 @@
Peripheral PTP Timer Test Application
=====================================
This tests setting the PTP timer to the following targets:
- one second into the future (using the absolute API)
- 1st of January 1970 0:00:00 (using the absolute API)
- This is expected to fire right away according to the API
- 1 µs to 99µs into the future (using the relative API)
If all timeouts fire within ± 10 µs of the target time, the test succeeds.
Expected Output on Success
--------------------------
main(): This is RIOT! (Version: <INSERT VERSION HERE>)
TEST SUCCEEDED!

View File

@ -0,0 +1,89 @@
/*
* Copyright (C) 2020 Otto-von-Guericke-Universität Magdeburg
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup tests
* @{
*
* @file
* @brief Peripheral PTP clock test application
*
* @author Marian Buschsieweke <marian.buschsieweke@ovgu.de>
*
* @}
*/
#include <stdint.h>
#include <stdlib.h>
#include "event.h"
#include "fmt.h"
#include "kernel_defines.h"
#include "periph/ptp.h"
static uint64_t ts_target;
static uint64_t ts_hit;
static const uint64_t max_diff = 10000; /* 10 µs */
static int failed = 0;
static unsigned n_timeouts = 0;
static event_queue_t q = EVENT_QUEUE_INIT_DETACHED;
static inline uint64_t abs_diff(uint64_t a, uint64_t b)
{
return (a >= b) ? (a - b) : (b - a);
}
static void ev_handler(event_t *ev)
{
(void)ev;
uint64_t diff = abs_diff(ts_target, ts_hit);
if (diff > max_diff) {
failed = 1;
print_str("Error: Timeout missed target by ");
print_u64_dec(diff);
print_str(" ns\n");
}
n_timeouts++;
if (n_timeouts == 1) {
/* check if setting timeout in the past does trigger IRQ */
ts_target = ptp_clock_read_u64();
ptp_timer_set_absolute_u64(0);
}
else if (n_timeouts < 100) {
/* check if setting small relative timeouts work */
uint64_t delay = (99 - n_timeouts) * 1000;
ts_target = ptp_clock_read_u64() + delay;
ptp_timer_set_u64(delay);
}
else {
if (failed) {
print_str("TEST FAILED!\n");
}
else {
print_str("TEST SUCCEEDED!\n");
}
}
}
void ptp_timer_cb(void)
{
ts_hit = ptp_clock_read_u64();
static event_t ev = { .handler = ev_handler };
event_post(&q, &ev);
}
int main(void)
{
ts_target = ptp_clock_read_u64() + NS_PER_SEC;
ptp_timer_set_absolute_u64(ts_target);
event_queue_claim(&q);
event_loop(&q);
UNREACHABLE();
}

View File

@ -0,0 +1,18 @@
#!/usr/bin/env python3
# Copyright (C) 2020 Otto-von-Guericke-Universität Magdeburg
#
# This file is subject to the terms and conditions of the GNU Lesser
# General Public License v2.1. See the file LICENSE in the top level
# directory for more details.
import sys
from testrunner import run
def testfunc(child):
child.expect_exact("TEST SUCCEEDED!\r\n")
if __name__ == "__main__":
sys.exit(run(testfunc))