|
Paparazzi UAS v7.0_unstable
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 dependency graph for sys_time.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. | |
| #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 | |
| 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.
Collaboration diagram for sys_time:| 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 56 of file sys_time.h.
| #define SYS_TIME_NB_TIMER 16 |
Definition at line 44 of file sys_time.h.
| #define SysTimeTimer | ( | _t | ) | ( get_sys_time_usec() - (_t)) |
Definition at line 257 of file sys_time.h.
| #define SysTimeTimerStart | ( | _t | ) | { _t = get_sys_time_usec(); } |
Definition at line 256 of file sys_time.h.
| #define SysTimeTimerStop | ( | _t | ) | { _t = ( get_sys_time_usec() - (_t)); } |
Definition at line 258 of file sys_time.h.
Definition at line 249 of file sys_time.h.
Definition at line 61 of file sys_time.h.
Definition at line 227 of file sys_time.h.
References sys_time::cpu_ticks_per_sec, and foo.
Referenced by ms2100_reset_cb(), and sys_tick_handler().
Here is the caller graph for this function:Definition at line 212 of file sys_time.h.
References sys_time::cpu_ticks_per_sec, and foo.
Referenced by sys_tick_handler().
Here is the caller graph for this function:Definition at line 217 of file sys_time.h.
References sys_time::cpu_ticks_per_sec, and foo.
Referenced by sys_time_usleep(), and xtend_rssi_periodic().
Here is the caller graph for this function:Get the time in seconds since startup.
Definition at line 168 of file sys_time.h.
References sys_time::cpu_ticks_per_sec, foo, sys_time::nb_sec, and sys_time::nb_sec_rem.
Referenced by accel_sp_cb(), actuators_faulhaber_periodic(), actuators_t4_uart_event(), actuators_uavcan_esc_status_cb(), agl_cb(), agl_dist_init(), airspeed_cb(), autopilot_arming_check_motors_on(), autopilot_arming_set(), baro_cb(), cc2500_delayMicroseconds(), check_anchor_timeout(), chirp_call(), ctrl_module_run(), dc_periodic(), ekf_run(), fill_anchor(), get_uavcan_status(), gps_cb(), gps_fix_valid(), guidance_indi_run_mode(), guidance_indi_run_mode(), gyro_cb(), hmc58xx_start_configure(), imu_aspirin2_configure_mag_slave(), imu_mpu9250_configure_mag_slave(), incidence_cb(), ins_flow_init(), ins_flow_update(), logger_control_effectiveness_periodic(), logger_file_write_row(), mag_cb(), nav_lace_run(), nav_rosette_run(), nav_rosette_setup(), nav_trinity_run(), optical_flow_landing_init(), periodic_report_sysmon(), periodic_sys_id_auto_doublets(), pfc_actuators_run(), PID_divergence_control(), pprz_bsem_wait_timeout(), preflight_check(), pressure_diff_cb(), px4flow_i2c_downlink(), px4flow_i2c_frame_cb(), read_rc_setpoint_heading(), reset_all_vars(), reset_horizontal_vars(), reset_vertical_vars(), rotwing_state_feedback_cb(), rotwing_state_hover_motors_idling(), rotwing_state_hover_motors_running(), rotwing_state_periodic(), rotwing_state_pusher_motor_running(), rotwing_state_skew_angle_valid(), rpm_cb(), stabilization_attitude_read_rc_setpoint_eulers(), stabilization_attitude_read_rc_setpoint_eulers_f(), start_chirp(), start_doublet(), start_wave(), stop_chirp(), stop_doublet(), stop_wave(), sys_id_auto_doublets_on_activation(), sys_id_chirp_activate_handler(), sys_id_chirp_init(), sys_id_chirp_run(), sys_id_doublet_activate_handler(), sys_id_doublet_init(), sys_id_doublet_run(), sys_id_wave_activate_handler(), sys_id_wave_frequency_hz_set(), sys_id_wave_init(), sys_id_wave_lag_rad_set(), sys_id_wave_run(), vel_sp_cb(), vertical_ctrl_module_run(), and vertical_ctrl_optical_flow_cb().
Get the time in milliseconds since startup.
Definition at line 100 of file sys_time_arch.c.
References cpu_counter, foo, msec_of_cpu_ticks(), sys_time::nb_sec, sys_time::nb_sec_rem, and startup_time.
Referenced by ak8975_event(), ak8975_read(), approach_moving_target_enable(), bf_millis(), collective_tracking_control(), dc_ctrl_parrot_mykonos_command(), dc_ctrl_parrot_mykonos_periodic(), decay_map(), distributed_circular(), follow_diagonal_approach(), follow_me_parse_target_pos(), follow_me_set_wp(), gps_piksi_event(), gvf_control_2D(), gvf_ik_control_2D(), gvf_parametric_control_2D(), hackhd_command(), hackhd_periodic(), init_random(), mavlink_send_attitude(), mavlink_send_attitude(), mavlink_send_attitude_quaternion(), mavlink_send_global_position_int(), mavlink_send_highres_imu(), mavlink_send_local_position_ned(), mavlink_send_rc_channels(), mavlink_send_set_mode(), mavlink_send_system_time(), parseThetaTable(), periodic_2Hz_openlog(), reset_gamma_t0(), sbp_pos_ecef_callback(), sbus_common_decode_event(), send_bluegiga(), send_downlink(), send_gvf(), send_gvf(), send_gvf_parametric(), spb_heartbeat_callback(), spektrum_init_sat(), spektrum_uart_check(), target_get_pos(), target_get_vel(), target_parse_target_pos(), target_pos_set_current_offset(), tunnel_event(), and wind_estimator_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:Get the time in microseconds since startup.
WARNING: overflows after 70min!
WARNING: overflows after 71min34seconds!
Definition at line 73 of file sys_time_arch.c.
References cpu_counter, foo, sys_time::nb_sec, sys_time::nb_sec_rem, startup_time, and usec_of_cpu_ticks().
Referenced by ahrs_aligner_run(), ahrs_vectornav_event(), apogee_baro_event(), ardrone_baro_event(), baro_amsys_read_event(), baro_bmp280_event(), baro_bmp3_event(), baro_bmp_event(), baro_ets_read_event(), baro_event(), baro_hca_read_event(), baro_mpl3115_read_event(), baro_MS5534A_event(), baro_ms5611_event(), baro_scp_event(), baro_sim_periodic(), bf_micros(), cloud_sensor_callback(), cloud_sim_detect(), decode_optical_flow_msg(), ekf_aw_propagate(), gps_cb(), gps_datalink_publish(), gps_feed_value(), gps_intermcu_parse_IMCU_REMOTE_GPS(), gps_mtk_msg(), gps_piksi_publish(), gps_sim_publish(), gps_sirf_msg(), gps_skytraq_msg(), gps_uavcan_cb(), gps_ubx_msg(), gps_ubx_parse_nav_relposned(), gps_udp_parse(), handle_ins_msg(), hott_periodic_event(), imu_apogee_event(), imu_aspirin2_event(), imu_aspirin_event(), imu_aspirin_i2c_event(), imu_bebop_event(), imu_bmi088_event(), imu_cube_event(), imu_disco_event(), imu_heater_run(), imu_mpu9250_event(), imu_mpu_hmc_event(), imu_mpu_i2c_event(), imu_mpu_spi_event(), imu_nps_event(), imu_px4_event(), imu_px4fmu_event(), ins_alt_float_update_baro(), ins_alt_float_update_gps(), ins_ekf2_parse_EXTERNAL_POSE(), ins_ext_pose_msg_update(), invensense2_config(), invensense2_parse_data(), invensense3_456_config(), invensense3_456_parse_fifo_data(), invensense3_config(), invensense3_parse_fifo_data(), invensense3_parse_reg_data(), laser_range_array_parse_msg(), lidar_lite_periodic(), lidar_sf11_periodic(), lidar_vl53l5cx_periodic(), lisa_l_baro_event(), LWC_callback(), mag_hmc58xx_module_event(), mag_ist8310_module_event(), mag_lis3mdl_module_event(), mag_pitot_parse_msg(), mag_qmc5883l_module_event(), mag_rm3100_module_event(), mag_uavcan_cb(), mag_uavcan_cb2(), main(), mateksys3901l0x_parse(), mavlink_send_gps_global_origin(), mavlink_send_gps_raw_int(), meteo_stick_event(), navdata_publish_imu(), navdata_update(), nmea_gps_msg(), nps_autopilot_run_step(), opticflow_module_run(), opticflow_pmw3901_event(), pose_periodic(), px4flow_i2c_frame_cb(), range_msg_callback(), range_sensor_uavcan_cb(), readRegister_nonblocking(), send_filter_status(), send_filter_status(), send_filter_status(), send_filter_status(), send_filter_status(), send_filter_status(), send_filter_status(), send_filter_status(), send_filter_status(), sensors_hitl_event(), sensors_hitl_parse_HITL_AIR_DATA(), sensors_hitl_parse_HITL_GPS(), sonar_adc_periodic(), sonar_bebop_event(), sonar_i2c_periodic(), sonar_pwm_read(), sonar_vl53l1x_publish(), stereocam_parse_msg(), sts3032_event(), superbitrf_event(), superbitrf_receive_packet_cb(), teraranger_event(), tfmini_i2c_periodic(), tfmini_send_abi(), v4l2_capture_thread(), and video_thread_function().
Here is the call graph for this function:Get the time in 100microseconds since startup.
WARNING: overflows after 7000min!
Get the time in 100microseconds since startup.
WARNING: overflows after 7000min!
WARNING: overflows after 7000 minutes!
Definition at line 89 of file sys_time_arch.c.
References cpu_counter, foo, sys_time::nb_sec, sys_time::nb_sec_rem, startup_time, and usec_of_cpu_ticks().
Referenced by pprzlog_tp_init().
Here is the call graph for this function:
Here is the caller graph for this function:Definition at line 232 of file sys_time.h.
References cpu_ticks, and sys_time::cpu_ticks_per_sec.
Referenced by get_sys_time_msec().
Here is the caller graph for this function:Definition at line 197 of file sys_time.h.
References ticks, and sys_time::ticks_per_sec.
Referenced by gps_tow_from_sys_ticks(), and windturbine_periodic().
Here is the caller graph for this function:Definition at line 242 of file sys_time.h.
References cpu_ticks, and sys_time::cpu_ticks_per_sec.
Definition at line 192 of file sys_time.h.
References sys_time::resolution, and ticks.
Definition at line 222 of file sys_time.h.
References sys_time::cpu_ticks_per_sec, and foo.
Initialize SysTick.
Generate SysTick interrupt every sys_time.resolution_cpu_ticks
Definition at line 54 of file sys_time_arch.c.
References AHB_CLK, CH_CFG_ST_FREQUENCY, sys_time::cpu_ticks_per_sec, foo, sys_time::resolution, sys_time::resolution_cpu_ticks, startup_time, sys_time_thread_main(), and thd_sys_tick().
Referenced by sys_time_init().
Here is the call graph for this function:
Here is the caller graph for this function:Cancel a system timer by id.
| id | Timer id. |
Definition at line 76 of file sys_time.c.
References sys_time_timer::cb, sys_time_timer::duration, sys_time_timer::elapsed, sys_time_timer::end_time, foo, sys_time_timer::in_use, and sys_time::timer.
Referenced by mavlink_mission_cancel_timer(), and px4flash_event().
Here is the caller graph for this function:Check if timer has elapsed.
| id | Timer id |
Definition at line 153 of file sys_time.h.
References sys_time_timer::elapsed, SYS_TIME_NB_TIMER, and sys_time::timer.
Referenced by main(), main_ap_periodic(), main_fbw_periodic(), main_recovery_periodic(), mavlink_mission_periodic(), and px4flash_event().
Here is the caller graph for this function:Definition at line 119 of file sys_time.c.
References sys_time_timer::cb, sys_time_timer::duration, sys_time_timer::elapsed, sys_time_timer::end_time, foo, sys_time_timer::in_use, sys_time::nb_sec, sys_time::nb_sec_rem, sys_time::nb_tick, sys_time::resolution, shell_add_entry(), 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().
Here is the call graph for this function:
Here is the caller graph for this function:Sleep.
| ms | milliseconds |
Definition at line 130 of file sys_time_arch.c.
References foo, and sys_time_usleep().
Referenced by uavcan_tx().
Here is the call graph for this function:
Here is the caller graph for this function:
|
extern |
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 intermcu_init(), main(), main_ap_init(), main_fbw_init(), main_init(), main_init(), main_init(), main_init(), main_init(), main_init(), main_init(), main_recovery_init(), mavlink_mission_set_timer(), and px4flash_init().
Here is the call graph for this function:
Here is the caller graph for this function:
|
extern |
Register a new system timer with an fixed offset from another one.
| timer | timer providing start time and duration |
| offset | offset in seconds beetween the timers (will overlap if longer than duration) |
| cb | Callback function that is called from the ISR when timer elapses, or NULL |
Definition at line 59 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, offset, SYS_TIME_NB_TIMER, sys_time_ticks_of_sec(), and sys_time::timer.
Referenced by main_ap_init().
Here is the call graph for this function:
Here is the caller graph for this function:Definition at line 182 of file sys_time.h.
References foo, and sys_time::ticks_per_sec.
Definition at line 177 of file sys_time.h.
References foo, and sys_time::ticks_per_sec.
Referenced by sys_tick_handler(), sys_time_register_timer(), sys_time_register_timer_offset(), and sys_time_update_timer().
Here is the caller graph for this function:Definition at line 187 of file sys_time.h.
References foo, and sys_time::ticks_per_sec.
Referenced by sys_tick_handler().
Here is the caller graph for this function:Update the duration until a timer elapses.
| id | Timer id |
| duration | Duration in seconds until the timer elapses. |
Definition at line 86 of file sys_time.c.
References sys_time_timer::duration, sys_time_timer::end_time, sys_time_ticks_of_sec(), and sys_time::timer.
Referenced by mavlink_mission_set_timer().
Here is the call graph for this function:
Here is the caller graph for this function:Sleep.
| us | microseconds |
Sleep.
using intermediate 64 bits variable to avoid wrapping
max sleep time is around 10 days (2^32 / CH_CFG_ST_FREQUENCY) at 10kHz
Sleep.
max value is limited by the max number of cycle i.e 2^32 * usec_of_cpu_ticks(systick_get_reload())
Definition at line 118 of file sys_time_arch.c.
References cpu_ticks_of_usec(), foo, and usec_of_cpu_ticks().
Referenced by bf_delayMicroseconds(), cyrf6936_init(), humid_sht_thd(), initializeSensor(), main(), pcap01_init(), px4flash_event(), readRegister_blocking(), received_spektrum_soft_bind(), send_spektrum_bind(), sht_read_humid(), sht_read_serial(), sht_read_temp(), spektrum_bind(), spektrum_try_bind(), sys_time_msleep(), VCOM_putchar(), video_thread_function(), w5100_init(), and xbee_dl_init().
Here is the call graph for this function:
Here is the caller graph for this function:Definition at line 237 of file sys_time.h.
References cpu_ticks, and sys_time::cpu_ticks_per_sec.
Referenced by get_sys_time_usec(), get_sys_time_usec100(), and sys_time_usleep().
Here is the caller graph for this function:Definition at line 202 of file sys_time.h.
References ticks, and sys_time::ticks_per_sec.
Definition at line 41 of file sys_time.c.