Paparazzi UAS  v5.10_stable-5-g83a0da5-dirty
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
sys_time_arch.h File Reference

Implementation of system time functions for ChibiOS arch. More...

#include "mcu_periph/sys_time.h"
#include <ch.h>
+ Include dependency graph for sys_time_arch.h:

Go to the source code of this file.

Functions

uint32_t get_sys_time_usec (void)
 Get the time in microseconds since startup. More...
 
uint32_t get_sys_time_msec (void)
 
void sys_time_usleep (uint32_t us)
 sys_time_usleep(uint32_t us) More...
 
void sys_time_msleep (uint16_t ms)
 
void sys_time_ssleep (uint8_t s)
 

Detailed Description

Implementation of system time functions for ChibiOS arch.

Mostly empty functions for Paparazzi compatibility, since ChibiOS uses different system time functions.

Definition in file sys_time_arch.h.

Function Documentation

uint32_t get_sys_time_usec ( void  )

Get the time in microseconds since startup.

WARNING: overflows after 70min!

Returns
microseconds since startup as uint32_t

Definition at line 68 of file sys_time_arch.c.

References sys_time::nb_sec, sys_time::nb_sec_rem, sys_time::nb_tick, and usec_of_sys_time_ticks().

Referenced by ahrs_aligner_run(), ahrs_gx3_publish_imu(), downlink_init(), gps_cb(), gps_feed_value(), gps_mtk_msg(), gps_piksi_publish(), gps_sim_hitl_event(), gps_sim_publish(), gps_sirf_msg(), gps_skytraq_msg(), gps_ubx_msg(), gps_udp_parse(), handle_ins_msg(), hott_periodic_event(), imu_analog_periodic(), imu_apogee_event(), imu_aspirin2_event(), imu_aspirin_event(), imu_aspirin_i2c_event(), imu_b2_event(), imu_bebop_event(), imu_drotek2_event(), imu_gl1_event(), imu_hbmini_event(), imu_krooz_event(), imu_krooz_periodic(), imu_mpu9250_event(), imu_mpu_hmc_event(), imu_mpu_i2c_event(), imu_mpu_spi_event(), imu_navgo_event(), imu_navstik_event(), imu_nps_event(), imu_ppzuav_event(), imu_px4_event(), imu_px4fmu_event(), imu_um6_publish(), imu_umarim_event(), ins_alt_float_update_baro(), ins_alt_float_update_gps(), ins_vectornav_propagate(), mag_hmc58xx_module_event(), mag_pitot_parse_msg(), main(), mavlink_send_gps_raw_int(), navdata_publish_imu(), nmea_gps_msg(), opticflow_module_run(), parse_gps_datalink(), parse_gps_datalink_small(), pose_periodic(), send_filter_status(), stereocam_to_state(), superbitrf_event(), superbitrf_receive_packet_cb(), and v4l2_capture_thread().

+ Here is the call graph for this function:

void sys_time_msleep ( uint16_t  ms)

Definition at line 101 of file sys_time_arch.c.

References CH_CFG_ST_FREQUENCY.

void sys_time_ssleep ( uint8_t  s)

Definition at line 107 of file sys_time_arch.c.

void sys_time_usleep ( uint32_t  us)

sys_time_usleep(uint32_t us)

using intermediate 64 bits variable to avoid wrapping

max sleep time is around 10 days (2^32 / CH_CFG_ST_FREQUENCY) at 10kHz

Definition at line 95 of file sys_time_arch.c.

References CH_CFG_ST_FREQUENCY.

Referenced by cyrf6936_init(), downlink_init(), main(), pcap01_init(), px4flash_event(), radio_control_spektrum_try_bind(), received_spektrum_soft_bind(), VCOM_putchar(), and w5100_init().

+ Here is the caller graph for this function: