Paparazzi UAS
v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
|
Architecture independent timing functions. More...
#include <inttypes.h>
#include <stdlib.h>
#include "std.h"
#include <BOARD_CONFIG>
#include "mcu_periph/sys_time_arch.h"
Go to the source code of this file.
Data Structures | |
struct | sys_time_timer |
struct | sys_time |
Macros | |
#define | SYS_TIME_NB_TIMER 16 |
#define | SYS_TIME_FREQUENCY 1000 |
(Default) sys_time timer frequency in Hz. More... | |
#define | USEC_OF_SEC(sec) ((sec) * 1e6) |
#define | SysTimeTimerStart(_t) { _t = get_sys_time_usec(); } |
#define | SysTimeTimer(_t) ( get_sys_time_usec() - (_t)) |
#define | SysTimeTimerStop(_t) { _t = ( get_sys_time_usec() - (_t)); } |
Typedefs | |
typedef int8_t | tid_t |
sys_time timer id type More... | |
typedef void(* | sys_time_cb) (uint8_t id) |
Variables | |
struct sys_time | sys_time |
Architecture independent timing functions.
Definition in file sys_time.h.
struct sys_time_timer |
Definition at line 63 of file sys_time.h.
Data Fields | ||
---|---|---|
sys_time_cb | cb | |
uint32_t | duration | in SYS_TIME_TICKS |
volatile bool | elapsed | |
uint32_t | end_time | in SYS_TIME_TICKS |
bool | in_use |
struct sys_time |
Definition at line 71 of file sys_time.h.
Data Fields | ||
---|---|---|
uint32_t | cpu_ticks_per_sec | cpu ticks per second |
volatile uint32_t | nb_sec | full seconds since startup |
volatile uint32_t | nb_sec_rem | remainder of seconds since startup in CPU_TICKS |
volatile uint32_t | nb_tick | SYS_TIME_TICKS since startup. |
float | resolution | sys_time_timer resolution in seconds |
uint32_t | resolution_cpu_ticks | sys_time_timer resolution in cpu ticks |
uint32_t | ticks_per_sec | sys_time ticks per second (SYS_TIME_FREQUENCY) |
struct sys_time_timer | timer[SYS_TIME_NB_TIMER] |
#define SYS_TIME_FREQUENCY 1000 |
(Default) sys_time timer frequency in Hz.
sys_time.resolution is set from this define.
Definition at line 55 of file sys_time.h.
#define SYS_TIME_NB_TIMER 16 |
Definition at line 40 of file sys_time.h.
#define SysTimeTimer | ( | _t | ) | ( get_sys_time_usec() - (_t)) |
Definition at line 219 of file sys_time.h.
#define SysTimeTimerStart | ( | _t | ) | { _t = get_sys_time_usec(); } |
Definition at line 218 of file sys_time.h.
#define SysTimeTimerStop | ( | _t | ) | { _t = ( get_sys_time_usec() - (_t)); } |
Definition at line 220 of file sys_time.h.
#define USEC_OF_SEC | ( | sec | ) | ((sec) * 1e6) |
Definition at line 210 of file sys_time.h.
typedef void(* sys_time_cb) (uint8_t id) |
Definition at line 61 of file sys_time.h.
sys_time timer id type
Definition at line 60 of file sys_time.h.
Definition at line 188 of file sys_time.h.
References sys_time::cpu_ticks_per_sec.
Referenced by ms2100_reset_cb(), and sys_tick_handler().
|
inlinestatic |
Definition at line 173 of file sys_time.h.
References sys_time::cpu_ticks_per_sec.
Definition at line 178 of file sys_time.h.
References sys_time::cpu_ticks_per_sec.
Referenced by sys_time_usleep(), and xtend_rssi_periodic().
|
inlinestatic |
Get the time in seconds since startup.
Definition at line 129 of file sys_time.h.
References sys_time::cpu_ticks_per_sec, sys_time::nb_sec, and sys_time::nb_sec_rem.
Referenced by accel_sp_cb(), agl_cb(), agl_dist_init(), airspeed_cb(), autopilot_arming_check_motors_on(), autopilot_arming_set(), baro_cb(), cc2500_delayMicroseconds(), check_anchor_timeout(), ctrl_module_run(), dc_periodic(), file_logger_write_row(), fill_anchor(), gps_cb(), guidance_indi_run(), gyro_cb(), hmc58xx_start_configure(), i2c_blocking_receive(), i2c_blocking_transceive(), i2c_blocking_transmit(), imu_aspirin2_configure_mag_slave(), imu_mpu9250_configure_mag_slave(), incidence_cb(), logger_control_effectiveness_periodic(), mag_cb(), periodic_report_sysmon(), pressure_diff_cb(), px4flow_i2c_downlink(), px4flow_i2c_frame_cb(), reset_all_vars(), reset_horizontal_vars(), reset_vertical_vars(), spi_blocking_transceive(), stabilization_attitude_read_rc_setpoint_eulers(), stabilization_attitude_read_rc_setpoint_eulers_f(), start_chirp(), stop_chirp(), sys_id_chirp_activate_handler(), sys_id_chirp_init(), sys_id_chirp_run(), and vertical_ctrl_module_run().
Definition at line 193 of file sys_time.h.
References sys_time::cpu_ticks_per_sec.
Referenced by get_sys_time_msec(), and TRIG_ISR().
Definition at line 158 of file sys_time.h.
References ticks, and sys_time::ticks_per_sec.
Referenced by get_sys_time_msec(), gps_tow_from_sys_ticks(), trigger_ext_periodic(), and windturbine_periodic().
Definition at line 203 of file sys_time.h.
References sys_time::cpu_ticks_per_sec.
|
inlinestatic |
Definition at line 153 of file sys_time.h.
References sys_time::resolution, and ticks.
Definition at line 183 of file sys_time.h.
References sys_time::cpu_ticks_per_sec.
void sys_time_arch_init | ( | void | ) |
Initialize SysTick.
Generate SysTick interrupt every sys_time.resolution_cpu_ticks
Definition at line 49 of file sys_time_arch.c.
References _VIC_ADDR, _VIC_CNTL, AHB_CLK, CH_CFG_ST_FREQUENCY, sys_time::cpu_ticks_per_sec, PCLK, sys_time::resolution, sys_time::resolution_cpu_ticks, startup_time, sys_time_thread_main(), T0CCR, T0EMR, T0MCR, T0MR0, T0PR, T0TCR, TCR_ENABLE, TCR_RESET, thd_sys_tick(), TIMER0_ISR(), TIMER0_VIC_SLOT, TMCR_MR0_I, VIC_BIT, VIC_ENABLE, VIC_TIMER0, VICIntEnable, and VICIntSelect.
Referenced by sys_time_init().
void sys_time_cancel_timer | ( | tid_t | id | ) |
Cancel a system timer by id.
id | Timer id. |
Definition at line 60 of file sys_time.c.
References sys_time_timer::cb, sys_time_timer::duration, sys_time_timer::elapsed, sys_time_timer::end_time, sys_time_timer::in_use, and sys_time::timer.
Referenced by mavlink_mission_cancel_timer(), and px4flash_event().
|
inlinestatic |
Check if timer has elapsed.
id | Timer id |
Definition at line 114 of file sys_time.h.
References sys_time_timer::elapsed, SYS_TIME_NB_TIMER, and sys_time::timer.
Referenced by handle_periodic_tasks(), handle_periodic_tasks_ap(), handle_periodic_tasks_fbw(), main(), mavlink_mission_periodic(), and px4flash_event().
void sys_time_init | ( | void | ) |
Definition at line 78 of file sys_time.c.
References sys_time_timer::cb, sys_time_timer::duration, sys_time_timer::elapsed, sys_time_timer::end_time, sys_time_timer::in_use, sys_time::nb_sec, sys_time::nb_sec_rem, sys_time::nb_tick, sys_time::resolution, sys_time_arch_init(), SYS_TIME_FREQUENCY, SYS_TIME_NB_TIMER, sys_time::ticks_per_sec, and sys_time::timer.
Referenced by main(), and mcu_init().
tid_t sys_time_register_timer | ( | float | duration, |
sys_time_cb | cb | ||
) |
Register a new system timer.
duration | Duration in seconds until the timer elapses. |
cb | Callback function that is called from the ISR when timer elapses, or NULL |
Definition at line 43 of file sys_time.c.
References sys_time_timer::cb, sys_time_timer::duration, sys_time_timer::elapsed, sys_time_timer::end_time, sys_time_timer::in_use, sys_time::nb_tick, start_time, SYS_TIME_NB_TIMER, sys_time_ticks_of_sec(), and sys_time::timer.
Referenced by init_ap(), init_fbw(), intermcu_init(), main(), main_init(), mavlink_mission_set_timer(), px4flash_event(), and px4flash_init().
Definition at line 143 of file sys_time.h.
References sys_time::ticks_per_sec.
|
inlinestatic |
Definition at line 138 of file sys_time.h.
References sys_time::ticks_per_sec.
Referenced by sys_tick_handler(), sys_time_register_timer(), and sys_time_update_timer().
Definition at line 148 of file sys_time.h.
References sys_time::ticks_per_sec.
Referenced by sys_tick_handler().
void sys_time_update_timer | ( | tid_t | id, |
float | duration | ||
) |
Update the duration until a timer elapses.
id | Timer id |
duration | Duration in seconds until the timer elapses. |
Definition at line 70 of file sys_time.c.
References sys_time_timer::duration, sys_time_timer::end_time, mcu_int_disable, mcu_int_enable, sys_time_ticks_of_sec(), and sys_time::timer.
Referenced by mavlink_mission_set_timer().
Definition at line 198 of file sys_time.h.
References sys_time::cpu_ticks_per_sec.
Referenced by get_sys_time_usec(), and sys_time_usleep().
Definition at line 163 of file sys_time.h.
References ticks, and sys_time::ticks_per_sec.
Referenced by get_sys_time_usec().
Definition at line 41 of file sys_time.c.