PX4 Firmware
PX4 Autopilot Software http://px4.io
|
High-resolution timer with callouts and timekeeping. More...
#include <sys/ioctl.h>
#include <sys/types.h>
#include <stdbool.h>
#include <inttypes.h>
#include <px4_platform_common/time.h>
#include <queue.h>
Go to the source code of this file.
Classes | |
struct | hrt_call |
Callout record. More... | |
Typedefs | |
typedef void(* | hrt_callout) (void *arg) |
Callout function type. More... | |
typedef struct hrt_call * | hrt_call_t |
Callout record. More... | |
Functions | |
__EXPORT hrt_abstime | hrt_absolute_time (void) |
Get absolute time in [us] (does not wrap). More... | |
__EXPORT hrt_abstime | ts_to_abstime (const struct timespec *ts) |
Convert a timespec to absolute time. More... | |
__EXPORT void | abstime_to_ts (struct timespec *ts, hrt_abstime abstime) |
Convert absolute time to a timespec. More... | |
static hrt_abstime | hrt_elapsed_time (const hrt_abstime *then) |
Compute the delta between a timestamp taken in the past and now. More... | |
__EXPORT hrt_abstime | hrt_elapsed_time_atomic (const volatile hrt_abstime *then) |
Compute the delta between a timestamp taken in the past and now. More... | |
__EXPORT hrt_abstime | hrt_store_absolute_time (volatile hrt_abstime *now) |
Store the absolute time in an interrupt-safe fashion. More... | |
__EXPORT void | hrt_call_after (struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg) |
Call callout(arg) after delay has elapsed. More... | |
__EXPORT void | hrt_call_at (struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg) |
Call callout(arg) at absolute time calltime. More... | |
__EXPORT void | hrt_call_every (struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg) |
Call callout(arg) after delay, and then after every interval. More... | |
__EXPORT bool | hrt_called (struct hrt_call *entry) |
If this returns true, the entry has been invoked and removed from the callout list, or it has never been entered. More... | |
__EXPORT void | hrt_cancel (struct hrt_call *entry) |
Remove the entry from the callout list. More... | |
__EXPORT void | hrt_call_init (struct hrt_call *entry) |
Initialise a hrt_call structure. More... | |
__EXPORT void | hrt_call_delay (struct hrt_call *entry, hrt_abstime delay) |
__EXPORT void | hrt_init (void) |
Variables | |
__BEGIN_DECLS typedef uint64_t | hrt_abstime |
Absolute time, in microsecond units. More... | |
High-resolution timer with callouts and timekeeping.
Definition in file drv_hrt.h.
typedef struct hrt_call * hrt_call_t |
Callout record.
typedef void(* hrt_callout) (void *arg) |
__EXPORT void abstime_to_ts | ( | struct timespec * | ts, |
hrt_abstime | abstime | ||
) |
Convert absolute time to a timespec.
Referenced by Simulator::handle_message_hil_sensor().
__EXPORT hrt_abstime hrt_absolute_time | ( | void | ) |
Get absolute time in [us] (does not wrap).
Referenced by vmount::InputMavlinkCmdMount::_ack_vehicle_command(), _auth_method_arm_req_check(), _auth_method_two_arm_check(), load_mon::LoadMon::_cpuload(), MavlinkFTP::_ensure_buffers_exist(), land_detector::MulticopterLandDetector::_get_landed_state(), land_detector::MulticopterLandDetector::_get_maybe_landed_state(), rpi_rc_in::RcInput::_measure(), linux_sbus::RcInput::_measure(), _param_notify_changes(), DfLtc2946Wrapper::_publish(), DfMS5607Wrapper::_publish(), DfMS5611Wrapper::_publish(), DfBmp280Wrapper::_publish(), DfBebopRangeFinderWrapper::_publish(), DfAK8963Wrapper::_publish(), DfHmc5883Wrapper::_publish(), DfTROneWrapper::_publish(), DfISL29501Wrapper::_publish(), DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfBebopBusWrapper::_publish(), DfMpu9250Wrapper::_publish(), ObstacleAvoidance::_publishVehicleCmdDoLoiter(), load_mon::LoadMon::_ram_used(), land_detector::LandDetector::_update_state(), FlightTasks::_updateCommand(), QShell::_wait_for_retval(), sensors::VotedSensorsUpdate::accelPoll(), px4::logger::Logger::ack_vehicle_command(), MavlinkReceiver::acknowledge(), FlightTask::activate(), Simulator::actuator_controls_from_outputs(), adc_measure(), BatteryStatus::adc_poll(), Sensors::adc_poll(), UavcanBarometerBridge::air_pressure_sub_cb(), events::SendEvent::answer_command(), answer_command(), arm_auth_request_msg_send(), arming_state_transition(), autosave_worker(), sensors::VotedSensorsUpdate::baroPoll(), battery_failsafe(), UavcanBatteryBridge::battery_sub_cb(), blink_msg_state(), launchdetection::CatapultLaunchMethod::CatapultLaunchMethod(), UavcanEscController::check_escs_status(), Commander::check_posvel_validity(), check_reboot(), BMI055_gyro::check_registers(), BMI055_accel::check_registers(), BMI088_gyro::check_registers(), BMI088_accel::check_registers(), BMI160::check_registers(), MPU9250::check_registers(), MPU6000::check_registers(), ICM20948::check_registers(), PrecLand::check_state_conditions(), MavlinkCommandSender::check_timeout(), Commander::check_valid(), Geofence::checkAll(), ObstacleAvoidance::checkAvoidanceProgress(), sensors::VotedSensorsUpdate::checkFailover(), BMP280::collect(), MS5525::collect(), TFMINI::collect(), ETSAirspeed::collect(), SDP3X::collect(), MEASAirspeed::collect(), SRF02::collect(), TERARANGER::collect(), CM8JL65::collect(), VL53LXX::collect(), LidarLiteI2C::collect(), Radar::collect(), MB12XX::collect(), MPL3115A2::collect(), SF1XX::collect(), PX4FLOW::collect(), SF0X::collect(), LSM303AGR::collect(), MS5611::collect(), LPS22HB::collect(), RM3100::collect(), MappyDot::collect(), LIS3MDL::collect(), INA226::collect(), LPS25H::collect(), QMC5883::collect(), HMC5883::collect(), BMM150::collect(), IST8310::collect(), BMP388::collect(), Commander::Commander(), FixedwingPositionControl::control_landing(), uORB::FastRpcChannel::control_msg_queue_add(), RoverPositionControl::control_position(), FixedwingPositionControl::control_position(), control_status_leds(), FixedwingPositionControl::control_takeoff(), controls_tick(), uORB::SubscriptionInterval::copy(), RCTest::crsfTest(), events::SendEvent::custom_command(), RCInput::cycle(), TAP_ESC::cycle(), Commander::data_link_check(), mpu9x50::data_ready_isr(), px4::logger::Logger::debug_print_buffer(), DShotTelemetry::decodeByte(), detect_orientation(), uORB::DeviceMaster::DeviceMaster(), Sensors::diff_pres_poll(), do_esc_calibration(), do_level_calibration(), dsm_config(), dsm_input(), GPS::dumpGpsData(), CameraTrigger::engage(), UavcanEscController::esc_status_sub_cb(), Commander::estimator_check(), MulticopterPositionControl::failsafe(), Navigator::fake_traffic(), uORB::KraitFastRpcChannel::fastrpc_recv_thread(), Tiltrotor::fill_actuator_outputs(), Tailsitter::fill_actuator_outputs(), Standard::fill_actuator_outputs(), fill_rc_input_msg(), UavcanFlowBridge::flow_sub_cb(), frsky_send_frame2(), frsky_telemetry_thread_main(), MulticopterAttitudeControl::generate_attitude_setpoint(), uORB::FastRpcChannel::get_bulk_data(), uORB::FastRpcChannel::get_data(), px4::logger::util::get_log_time(), CollisionPrevention::getElapsedTime(), FlightTask::getPositionSetpoint(), DShotTelemetry::getRequestMotorIndex(), CollisionPrevention::getTime(), UavcanGnssBridge::gnss_auxiliary_sub_cb(), CameraCapture::gpio_interrupt_routine(), sensors::VotedSensorsUpdate::gyroPoll(), Commander::handle_command(), VtolAttitudeControl::handle_command(), Commander::handle_command_motor_test(), MavlinkParametersManager::handle_message(), MavlinkTimesync::handle_message(), MavlinkReceiver::handle_message_adsb_vehicle(), MavlinkReceiver::handle_message_battery_status(), MavlinkReceiver::handle_message_cellular_status(), MavlinkReceiver::handle_message_collision(), MavlinkReceiver::handle_message_command_ack(), MavlinkReceiver::handle_message_command_int(), MavlinkReceiver::handle_message_command_long(), MavlinkReceiver::handle_message_debug(), MavlinkReceiver::handle_message_debug_float_array(), MavlinkReceiver::handle_message_debug_vect(), MavlinkReceiver::handle_message_distance_sensor(), MavlinkReceiver::handle_message_follow_target(), MavlinkReceiver::handle_message_gps_global_origin(), MavlinkReceiver::handle_message_heartbeat(), MavlinkReceiver::handle_message_hil_gps(), MavlinkReceiver::handle_message_hil_optical_flow(), MavlinkReceiver::handle_message_hil_sensor(), Simulator::handle_message_hil_sensor(), MavlinkReceiver::handle_message_hil_state_quaternion(), Simulator::handle_message_hil_state_quaternion(), Simulator::handle_message_landing_target(), MavlinkReceiver::handle_message_manual_control(), MavlinkReceiver::handle_message_named_value_float(), MavlinkReceiver::handle_message_obstacle_distance(), MavlinkReceiver::handle_message_onboard_computer_status(), MavlinkReceiver::handle_message_optical_flow_rad(), MavlinkReceiver::handle_message_ping(), MavlinkReceiver::handle_message_radio_status(), MavlinkReceiver::handle_message_rc_channels_override(), MavlinkReceiver::handle_message_set_actuator_control_target(), MavlinkReceiver::handle_message_set_attitude_target(), MavlinkReceiver::handle_message_set_mode(), MavlinkReceiver::handle_message_set_position_target_global_int(), MavlinkReceiver::handle_message_set_position_target_local_ned(), MavlinkReceiver::handle_message_statustext(), MavlinkReceiver::handle_message_trajectory_representation_waypoints(), MavlinkReceiver::handle_message_utm_global_position(), MavlinkMissionManager::handle_mission_ack(), MavlinkMissionManager::handle_mission_clear_all(), MavlinkMissionManager::handle_mission_count(), MavlinkMissionManager::handle_mission_item_both(), MavlinkMissionManager::handle_mission_request_both(), MavlinkMissionManager::handle_mission_request_list(), MavlinkMissionManager::handle_mission_set_current(), PX4IO::handle_motor_test(), MavlinkULog::handle_update(), MavlinkCommandSender::handle_vehicle_command(), DShotOutput::handleNewTelemetryData(), px4::Replay::handleTopicDelay(), hrt_elapsed_time(), runwaytakeoff::RunwayTakeoff::init(), PMW3901::init(), PAW3902::init(), MulticopterPositionControl::init(), TAP_ESC::init(), LeddarOne::init(), PX4IO::init(), MPU9250::init(), ICM20948::init(), px4muorb::KraitRpcWrapper::Initialize(), px4::logger::Logger::initialize_load_output(), ObstacleAvoidance::injectAvoidanceSetpoints(), Sih::inner_loop(), PX4IO::io_get_raw_rc_input(), PX4IO::io_handle_status(), PX4IO::io_handle_vservo(), PX4IO::io_publish_pwm_outputs(), MissionBlock::is_mission_item_reached(), MissionBlock::issue_command(), FixedwingPositionControl::landing_status_publish(), uORBTest::UnitTest::latency_test(), led_init(), UavcanMagnetometerBridge::mag2_sub_cb(), mag_calibration_worker(), UavcanMagnetometerBridge::mag_sub_cb(), sensors::VotedSensorsUpdate::magPoll(), HRTTest::main(), main_state_transition(), Mavlink::Mavlink(), Mavlink::mavlink_open_uart(), mavlink_vasprintf(), MavlinkStream::MavlinkStream(), MavlinkULog::MavlinkULog(), LidarLitePWM::measure(), AK09916::measure(), LidarLiteI2C::measure(), ADIS16477::measure(), FXAS21002C::measure(), ICM20948_mag::measure(), ADIS16448::measure(), MPU9250_mag::measure(), LeddarOne::measure(), ADIS16497::measure(), VOXLPM::measure(), BMA180::measure(), BMI055_gyro::measure(), BMI055_accel::measure(), BMI088_gyro::measure(), BMI088_accel::measure(), L3GD20::measure(), MPU9250::measure(), BMI160::measure(), MPU6000::measure(), ICM20948::measure(), LSM303D::measureAccelerometer(), LSM303D::measureMagnetometer(), Commander::mission_init(), MissionBlock::mission_item_to_position_setpoint(), MixerTest::mixerTest(), MK::mk_servo_locate(), motor_ramp_thread_main(), motor_test(), MixingOutput::motorTest(), nshterm_main(), Commander::offboard_control_update(), GpsFailure::on_activation(), PrecLand::on_activation(), GpsFailure::on_active(), FollowTarget::on_active(), UavcanEscController::orb_pub_timer_cb(), output_limit_calc(), vmount::OutputBase::OutputBase(), perf_begin(), perf_count(), perf_end(), events::rc_loss::RC_Loss_Alarm::play_tune(), power_button_state_notification_cb(), print_reject_arm(), print_reject_mode(), px4::logger::Logger::print_statistics(), uORB::DeviceMaster::printStatistics(), UavcanGnssBridge::process_fixx(), uORBTest::UnitTest::pub_test_multi2_main(), events::status::StatusDisplay::publish(), PWMIN::publish(), MavlinkULog::publish_ack(), Simulator::publish_distance_topic(), Simulator::publish_flow_topic(), publish_gam_message(), IridiumSBD::publish_iridium_status(), publish_led_control(), TemperatureCalibration::publish_led_control(), px4::logger::LogWriterMavlink::publish_message(), Navigator::publish_mission_result(), Simulator::publish_odometry_topic(), Navigator::publish_position_setpoint_triplet(), MulticopterAttitudeControl::publish_rates_setpoint(), Sih::publish_sih(), IridiumSBD::publish_subsystem_status(), Mavlink::publish_telemetry_status(), publish_tune_control(), Navigator::publish_vehicle_cmd(), Navigator::publish_vehicle_command_ack(), TimestampedList< MavlinkCommandSender::command_item_t >::put(), Integrator::put_with_interval(), pwmin_test(), px4muorb_get_absolute_time(), PWMIN::read(), IRLOCK::read_device(), GPSSIM::receive(), DShotTelemetry::redirectOutput(), registers_set(), MPU9250::reset(), MPU6000::reset(), ICM20948::reset(), Mission::reset_mission(), rgbled_set_color_and_mode(), VehicleAcceleration::Run(), VehicleAngularVelocity::Run(), SafetyButton::Run(), Sih::run(), px4::Replay::run(), ADC::Run(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), RCUpdate::RCUpdate::Run(), AttitudeEstimatorQ::Run(), CameraCapture::Run(), AirspeedModule::Run(), Commander::run(), FixedwingAttitudeControl::Run(), RoverPositionControl::run(), MulticopterPositionControl::Run(), VtolAttitudeControl::Run(), PAW3902::Run(), Sensors::run(), Navigator::run(), UavcanServers::run(), px4::logger::Logger::run(), GPS::run(), FXOS8701CQ::Run(), px4::logger::LogWriterFile::run(), PMW3901::Run(), FixedwingPositionControl::Run(), SF0X::Run(), land_detector::LandDetector::Run(), UavcanNode::Run(), BlockLocalPositionEstimator::Run(), MavlinkReceiver::Run(), CameraTrigger::Run(), BATT_SMBUS::Run(), PGA460::run(), PrecLand::run_state_horizontal_approach(), PrecLand::run_state_search(), PrecLand::run_state_start(), Mission::save_mission_state(), IridiumSBD::sbdsession_loop(), sbus1_output(), RCTest::sbus2Test(), sbus_config(), sbus_input(), schedule_reboot(), MavlinkStreamSystemTime::send(), MavlinkStreamTimesync::send(), MavlinkStreamCameraTrigger::send(), MavlinkStreamHILActuatorControls::send(), MavlinkStreamPositionTargetGlobalInt::send(), MavlinkStreamAltitude::send(), MavlinkStreamPing::send(), Mavlink::send_bytes(), MavlinkReceiver::send_flight_information(), uORB::FastRpcChannel::send_message(), uORB::KraitFastRpcChannel::send_message(), MavlinkMissionManager::send_mission_count(), MavlinkMissionManager::send_mission_item(), MavlinkMissionManager::send_mission_request(), MavlinkReceiver::send_storage_information(), MavlinkParametersManager::send_untransmitted(), MulticopterPositionControl::send_vehicle_cmd_do(), send_vehicle_command(), FlightTaskOrbit::sendTelemetry(), sensors::VotedSensorsUpdate::sensorsPoll(), Commander::set_home_position(), Commander::set_home_position_alt_only(), set_tune(), set_tune_override(), PX4IO::set_update_rate(), MixingOutput::setAndPublishActuatorOutputs(), uORB::DeviceMaster::showTop(), Simulator::Simulator(), PrecLand::slewrate(), IridiumSBD::standby_loop(), IridiumSBD::start_csq(), px4::logger::Logger::start_log_file(), IridiumSBD::start_sbd_session(), IridiumSBD::status(), FixedwingPositionControl::status_publish(), events::rc_loss::RC_Loss_Alarm::stop_tune(), PrecLand::switch_to_state_descend_above_target(), PrecLand::switch_to_state_done(), PrecLand::switch_to_state_fallback(), PrecLand::switch_to_state_final_approach(), PrecLand::switch_to_state_horizontal_approach(), PrecLand::switch_to_state_search(), PrecLand::switch_to_state_start(), MavlinkTimesync::sync_stamp(), task_main(), spektrum_rc::task_main(), TemperatureCalibration::task_main(), rc_receiver::task_main(), uart_esc::task_main(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), MK::task_main(), PX4IO::task_main(), Mavlink::task_main(), RoboClaw::taskMain(), FixedwingPositionControl::tecs_status_publish(), FixedwingPositionControl::tecs_update_pitch_throttle(), IRLOCK::test(), CameraTrigger::test(), TEST_F(), test_file(), test_hrt(), IridiumSBD::test_loop(), test_rc(), test_time(), test_uart_send(), time_fsync(), top_main(), tune_failsafe(), tune_home_set(), tune_mission_fail(), tune_mission_ok(), tune_negative(), tune_neutral(), tune_positive(), PGA460::uORB_publish_results(), launchdetection::CatapultLaunchMethod::update(), vmount::OutputMavlink::update(), vmount::OutputRC::update(), PX4Gyroscope::update(), DShotTelemetry::update(), landing_target_estimator::LandingTargetEstimator::update(), MavlinkStream::update(), LedController::update(), MavlinkMissionManager::update_active_mission(), Commander::update_control_mode(), TimestampedList< MavlinkCommandSender::command_item_t >::update_current(), MavlinkStreamHighLatency2::update_data(), VtolType::update_fw_state(), Simulator::update_gps(), vmount::InputMavlinkCmdMount::update_impl(), update_mem_usage(), OSDatxxxx::update_screen(), TemperatureCalibrationAccel::update_sensor_instance(), TemperatureCalibrationGyro::update_sensor_instance(), TemperatureCalibrationBaro::update_sensor_instance(), OSDatxxxx::update_topics(), Tiltrotor::update_transition_state(), Tailsitter::update_transition_state(), Standard::update_transition_state(), Tiltrotor::update_vtol_state(), Tailsitter::update_vtol_state(), Standard::update_vtol_state(), FailureDetector::updateAttitudeStatus(), ObstacleAvoidance::updateAvoidanceDesiredWaypoints(), FlightTask::updateInitialize(), MixingOutput::updateOutputSlewrate(), user_start(), MuorbTestExample::uSleepTest(), MicroBenchHRT::ut_declare_test_c(), FixedwingAttitudeControl::vehicle_manual_poll(), MulticopterPositionControl::warn_rate_limited(), px4::logger::watchdog_update(), uORB::DeviceNode::write(), IridiumSBD::write(), px4::logger::Logger::write_header(), px4::logger::Logger::write_load_output(), px4::logger::Logger::write_message(), and write_test().
__EXPORT void hrt_call_after | ( | struct hrt_call * | entry, |
hrt_abstime | delay, | ||
hrt_callout | callout, | ||
void * | arg | ||
) |
Call callout(arg) after delay has elapsed.
If callout is NULL, this can be used to implement a timeout by testing the call with hrt_called().
Referenced by TEST_PPM::do_out(), PWMIN::hard_reset(), hrt_elapsed_time(), HRTTest::main(), CameraTrigger::Run(), CameraTrigger::shoot_once(), TEST_PPM::start(), test_hrt(), timer_expired(), and CameraTrigger::toggle_power().
__EXPORT void hrt_call_at | ( | struct hrt_call * | entry, |
hrt_abstime | calltime, | ||
hrt_callout | callout, | ||
void * | arg | ||
) |
Call callout(arg) at absolute time calltime.
Referenced by hrt_elapsed_time().
__EXPORT void hrt_call_delay | ( | struct hrt_call * | entry, |
hrt_abstime | delay | ||
) |
__EXPORT void hrt_call_every | ( | struct hrt_call * | entry, |
hrt_abstime | delay, | ||
hrt_abstime | interval, | ||
hrt_callout | callout, | ||
void * | arg | ||
) |
Call callout(arg) after delay, and then after every interval.
Note thet the interval is timed between scheduled, not actual, call times, so the call rate may jitter but should not drift.
Referenced by CameraTrigger::enable_keep_alive(), failsafe_led_init(), hrt_elapsed_time(), PWMIN::init(), Sih::run(), UavcanEsc::run(), UavcanNode::run(), px4::logger::Logger::run(), safety_init(), CameraTrigger::update_intervalometer(), and user_start().
Initialise a hrt_call structure.
Referenced by hrt_elapsed_time().
If this returns true, the entry has been invoked and removed from the callout list, or it has never been entered.
Always returns false for repeating callouts.
Referenced by hrt_elapsed_time(), HRTTest::main(), and test_hrt().
Remove the entry from the callout list.
Referenced by CameraTrigger::enable_keep_alive(), hrt_elapsed_time(), HRTTest::main(), Sih::run(), UavcanEsc::run(), UavcanNode::run(), px4::logger::Logger::run(), CameraTrigger::Run(), TEST_PPM::stop(), and CameraTrigger::stop().
|
inlinestatic |
Compute the delta between a timestamp taken in the past and now.
This function is not interrupt save.
Definition at line 102 of file drv_hrt.h.
References __END_DECLS, hrt_call::arg, hrt_call::callout, hrt_absolute_time(), hrt_abstime, hrt_call_after(), hrt_call_at(), hrt_call_delay(), hrt_call_every(), hrt_call_init(), hrt_called(), hrt_cancel(), hrt_elapsed_time_atomic(), hrt_init(), and hrt_store_absolute_time().
Referenced by load_mon::LoadMon::_cpuload(), PWMIN::_freeze_test(), land_detector::MulticopterLandDetector::_get_ground_contact_state(), land_detector::VtolLandDetector::_get_landed_state(), land_detector::FixedwingLandDetector::_get_landed_state(), land_detector::MulticopterLandDetector::_get_maybe_landed_state(), land_detector::MulticopterLandDetector::_has_altitude_lock(), land_detector::MulticopterLandDetector::_is_climb_rate_enabled(), DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), QShell::_wait_for_retval(), PreFlightCheck::accelerometerCheck(), adc_measure(), FixedwingPositionControl::airspeed_poll(), PreFlightCheck::airspeedCheck(), uORB::DeviceNode::appears_updated(), arm_disarm(), arming_state_transition(), PreFlightCheck::baroCheck(), Commander::battery_status_check(), Commander::check_posvel_validity(), MavlinkCommandSender::check_timeout(), Geofence::checkAll(), TFMINI::collect(), LidarLiteI2C::collect(), SF0X::collect(), commander_low_prio_loop(), FixedwingPositionControl::control_landing(), RoverPositionControl::control_position(), FixedwingPositionControl::control_position(), control_status_leds(), FixedwingPositionControl::control_takeoff(), Commander::data_link_check(), Mavlink::display_status(), do_esc_calibration(), do_level_calibration(), Commander::estimator_check(), FixedwingAttitudeControl::get_airspeed_and_update_scaling(), Mavlink::get_free_tx_buf(), runwaytakeoff::RunwayTakeoff::getThrottle(), PreFlightCheck::gyroCheck(), Simulator::handle_message_hil_sensor(), PX4IO::handle_motor_test(), MavlinkULog::handle_update(), FixedwingPositionControl::in_takeoff_situation(), PX4IO::init(), ObstacleAvoidance::injectAvoidanceSetpoints(), PX4IO::io_set_control_state(), Mavlink::is_connected(), PreFlightCheck::magnometerCheck(), mixer_tick(), MixerTest::mixerTest(), motor_ramp_thread_main(), MixingOutput::motorTest(), GpsFailure::on_active(), PrecLand::on_active(), output_limit_calc(), param_autosave(), param_print_status(), PreFlightCheck::powerCheck(), ppm_input(), Commander::preflight_check(), RCInput::print_status(), UavcanGnssBridge::process_fixx(), px4::logger::LogWriterMavlink::publish_message(), px4::Replay::run(), MulticopterRateControl::Run(), RCUpdate::RCUpdate::Run(), AttitudeEstimatorQ::Run(), Commander::run(), FixedwingAttitudeControl::Run(), Sensors::run(), Navigator::run(), FXOS8701CQ::Run(), LidarLiteI2C::Run(), LSM303D::Run(), land_detector::LandDetector::Run(), MavlinkReceiver::Run(), MavlinkFTP::send(), MavlinkMissionManager::send(), MavlinkStreamAltitude::send(), Mavlink::send_packet(), PX4IO::set_update_rate(), shutdown_if_allowed(), Mavlink::task_main(), FixedwingPositionControl::tecs_update_pitch_throttle(), time_fsync(), launchdetection::CatapultLaunchMethod::update(), PX4Gyroscope::update(), runwaytakeoff::RunwayTakeoff::update(), Mavlink::update_rate_mult(), uORB::SubscriptionInterval::updated(), px4::logger::LogWriterFile::write(), px4::logger::Logger::write_message(), and write_test().
__EXPORT hrt_abstime hrt_elapsed_time_atomic | ( | const volatile hrt_abstime * | then | ) |
Compute the delta between a timestamp taken in the past and now.
This function is safe to use even if the timestamp is updated by an interrupt during execution.
Referenced by uORB::SubscriptionCallbackWorkItem::call(), controls_tick(), hrt_elapsed_time(), HRTTest::main(), uORBTest::UnitTest::pubsublatency_main(), and MicroBenchHRT::ut_declare_test_c().
__EXPORT void hrt_init | ( | void | ) |
__EXPORT hrt_abstime hrt_store_absolute_time | ( | volatile hrt_abstime * | now | ) |
Store the absolute time in an interrupt-safe fashion.
This function ensures that the timestamp cannot be seen half-written by an interrupt handler.
Referenced by hrt_elapsed_time().
__EXPORT hrt_abstime ts_to_abstime | ( | const struct timespec * | ts | ) |
Convert a timespec to absolute time.
__BEGIN_DECLS typedef uint64_t hrt_abstime |
Absolute time, in microsecond units.
Absolute time is measured from some arbitrary epoch shortly after system startup. It should never wrap or go backwards.
Definition at line 58 of file drv_hrt.h.
Referenced by _auth_method_arm_req_check(), _auth_method_two_arm_check(), MavlinkFtpTest::_burst_test(), CollisionPrevention::_calculateConstrainedSetpoint(), load_mon::LoadMon::_cpuload(), FlightTaskManual::_evaluateSticks(), land_detector::MulticopterLandDetector::_get_maybe_landed_state(), DfLtc2946Wrapper::_publish(), DfBebopBusWrapper::_publish(), MavlinkFtpTest::_receive_message_handler_burst(), land_detector::MulticopterLandDetector::_update_params(), land_detector::LandDetector::_update_state(), QShell::_wait_for_retval(), adc_measure(), Sensors::adc_poll(), UavcanEscController::check_escs_status(), Commander::check_valid(), BMP280::collect(), TFMINI::collect(), CM8JL65::collect(), LidarLiteI2C::collect(), BMP388::collect(), uORB::FastRpcChannel::control_msg_queue_add(), control_status_leds(), uORB::DeviceNode::copy_and_get_timestamp(), RCTest::crsfTest(), RCInput::cycle(), TAP_ESC::cycle(), detect_orientation(), do_esc_calibration(), do_level_calibration(), dsm_input(), uORB::KraitFastRpcChannel::fastrpc_recv_thread(), frsky_telemetry_thread_main(), Battery::full_cell_voltage(), uORB::FastRpcChannel::get_bulk_data(), uORB::FastRpcChannel::get_data(), MavlinkStream::get_interval(), DShotOutput::get_mode(), PX4FMU::get_mode(), systemlib::Hysteresis::get_state(), Simulator::handle_message_hil_sensor(), MavlinkReceiver::handle_message_ping(), MavlinkULog::handle_update(), hrt_elapsed_time(), FixedwingPositionControl::in_takeoff_situation(), TAP_ESC::init(), LeddarOne::init(), PX4IO::init(), px4::logger::Logger::initialize_load_output(), ObstacleAvoidance::injectAvoidanceSetpoints(), uORB::DeviceNode::ioctl(), MissionBlock::is_mission_item_reached(), mag_calibration_worker(), HRTTest::main(), mavlink_get_channel_buffer(), LidarLitePWM::measure(), AK09916::measure(), ADIS16477::measure(), FXAS21002C::measure(), ICM20948_mag::measure(), ADIS16448::measure(), MPU9250_mag::measure(), ADIS16497::measure(), VOXLPM::measure(), BMI055_gyro::measure(), BMI055_accel::measure(), BMI088_gyro::measure(), BMI088_accel::measure(), L3GD20::measure(), MPU9250::measure(), BMI160::measure(), MPU6000::measure(), ICM20948::measure(), LSM303D::measureAccelerometer(), LSM303D::measureMagnetometer(), mixer_tick(), MixerTest::mixerTest(), motor_ramp_thread_main(), output_limit_calc(), param_autosave(), perf_count(), print_reject_arm(), print_reject_mode(), uORB::DeviceMaster::printStatistics(), px4::logger::LogWriterMavlink::publish_message(), TimestampedList< MavlinkCommandSender::command_item_t >::put(), Integrator::put_with_interval(), Sih::run(), ADC::Run(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), AttitudeEstimatorQ::Run(), Commander::run(), MulticopterPositionControl::Run(), PAW3902::Run(), Ekf2::Run(), Navigator::run(), px4::logger::Logger::run(), FXOS8701CQ::Run(), px4::logger::LogWriterFile::run(), land_detector::LandDetector::Run(), MavlinkReceiver::Run(), sbus1_output(), RCTest::sbus2Test(), sbus_input(), uORB::FastRpcChannel::send_message(), uORB::KraitFastRpcChannel::send_message(), MavlinkRateLimiter::set_interval(), PX4Rangefinder::set_min_distance(), PX4Magnetometer::set_sensitivity(), PX4Barometer::set_temperature(), PX4Accelerometer::set_temperature(), PX4Gyroscope::set_temperature(), PX4IO::set_update_rate(), Takeoff::setSpoolupTime(), uORB::DeviceMaster::showTop(), task_main(), spektrum_rc::task_main(), TemperatureCalibration::task_main(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), PX4IO::task_main(), Mavlink::task_main(), TEST(), TEST_F(), test_file(), test_hrt(), uORBTest::UnitTest::test_multi2(), test_time(), time_fsync(), top_main(), vmount::OutputMavlink::update(), vmount::OutputRC::update(), systemlib::Hysteresis::update(), DShotTelemetry::update(), LedController::update(), MavlinkStreamHighLatency2::update_data(), vmount::InputMavlinkCmdMount::update_impl(), FailureDetector::updateAttitudeStatus(), MixingOutput::updateLatencyPerfCounter(), MixingOutput::updateOutputSlewrate(), MulticopterPositionControl::warn_rate_limited(), px4::logger::watchdog_update(), px4::logger::Logger::write_load_output(), and write_test().