Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

HRT: Create new separate call for atomic HRT elapsed time calculation #11248

Merged
merged 10 commits into from
Jan 22, 2019

Conversation

LorenzMeier
Copy link
Member

@LorenzMeier LorenzMeier commented Jan 20, 2019

This call rarely needs to be truly atomic and the involved CPU overhead in making it atomic was unnecessary and introduces a lot of IRQ jitter with no value-add. The call has been moved to be non-atomic and the codebase will be inspected and changed in follow-up commits for the few instances where it is truly needed.

Fixes #11245.

After fix (more CPU idle = better):
screenshot 2019-01-19 at 21 37 45

Current:
screenshot 2019-01-19 at 21 45 14

This call rarely needs to be truly atomic and the involved CPU overhead in making it atomic was unnecessary and introduces a lot of IRQ jitter with no value-add. The call has been moved to be non-atomic and the codebase will be inspected and changed in follow-up commits for the few instances where it is truly needed.
This ensures we get absolutely accurate timing.
@LorenzMeier
Copy link
Member Author

On first pass I didn't find any critical code really requiring atomic operation - but we need to review this carefully. Search for hrt_elapsed_time( to find possible offenders. For me this found:

Searching 2690 files for "hrt_elapsed_time("

/Users/lorenzmeier/src/Firmware/src/drivers/distance_sensor/sf0x/sf0x.cpp:
  469  
  470  	/* clear buffer if last read was too long ago */
  471: 	int64_t read_elapsed = hrt_elapsed_time(&_last_read);
  472  
  473  	/* the buffer for read chars is buflen minus null termination */

/Users/lorenzmeier/src/Firmware/src/drivers/distance_sensor/tfmini/tfmini.cpp:
  476  
  477  	/* clear buffer if last read was too long ago */
  478: 	int64_t read_elapsed = hrt_elapsed_time(&_last_read);
  479  
  480  	/* the buffer for read chars is buflen minus null termination */

/Users/lorenzmeier/src/Firmware/src/drivers/drv_hrt.h:
   99   * This function is not interrupt save.
  100   */
  101: __EXPORT extern hrt_abstime hrt_elapsed_time(const volatile hrt_abstime *then);
  102  
  103  /**

/Users/lorenzmeier/src/Firmware/src/drivers/kinetis/drv_hrt.c:
  599   */
  600  hrt_abstime
  601: hrt_elapsed_time(const volatile hrt_abstime *then)
  602  {
  603  	irqstate_t flags = px4_enter_critical_section();

/Users/lorenzmeier/src/Firmware/src/drivers/pwm_input/pwm_input.cpp:
  384  {
  385  	/* reset if last poll time was way back and a read was recently requested */
  386: 	if (hrt_elapsed_time(&_last_poll_time) > TIMEOUT_POLL && hrt_elapsed_time(&_last_read_time) < TIMEOUT_READ) {
  387  		hard_reset();
  388  	}

/Users/lorenzmeier/src/Firmware/src/drivers/px4io/px4io.cpp:
  609  		px4_usleep(2000);
  610  		protocol = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION);
  611: 	} while (protocol == _io_reg_get_error && (hrt_elapsed_time(&start_try_time) < 700U * 1000U));
  612  
  613  	/* if the error still persists after timing out, we give up */
  ...
 1283  			if (changed) {
 1284  				orb_copy(ORB_ID(actuator_controls_0), _t_actuator_controls_0, &controls);
 1285: 				perf_set_elapsed(_perf_sample_latency, hrt_elapsed_time(&controls.timestamp_sample));
 1286  			}
 1287  		}
 ....
 3299  			const unsigned long timeout = 5000000;
 3300  
 3301: 			while (hrt_elapsed_time(&start) < timeout) {
 3302  				fds.fd = 0; /* stdin */
 3303  				fds.events = POLLIN;
 ....
 3320  			}
 3321  
 3322: 			if (hrt_elapsed_time(&start) > timeout) {
 3323  				errx(1, "TIMEOUT! ABORTED WITHOUT CHANGES.");
 3324  			}

/Users/lorenzmeier/src/Firmware/src/drivers/qshell/posix/qshell.cpp:
  123  	const hrt_abstime time_started_us = hrt_absolute_time();
  124  
  125: 	while (hrt_elapsed_time(&time_started_us) < 3000000) {
  126  		bool updated;
  127  		orb_check(_sub_qshell_retval, &updated);

/Users/lorenzmeier/src/Firmware/src/drivers/rc_input/RCInput.cpp:
  799  	perf_print_counter(_publish_interval_perf);
  800  
  801: 	if (hrt_elapsed_time(&_rc_in.timestamp) < 1_s) {
  802  		print_message(_rc_in);
  803  	}

/Users/lorenzmeier/src/Firmware/src/drivers/samv7/drv_hrt.c:
  680   */
  681  hrt_abstime
  682: hrt_elapsed_time(const volatile hrt_abstime *then)
  683  {
  684  	irqstate_t flags = enter_critical_section();

/Users/lorenzmeier/src/Firmware/src/drivers/stm32/drv_hrt.c:
  720   */
  721  hrt_abstime
  722: hrt_elapsed_time(const volatile hrt_abstime *then)
  723  {
  724  	hrt_abstime delta = hrt_absolute_time() - *then;

/Users/lorenzmeier/src/Firmware/src/examples/bottle_drop/bottle_drop.cpp:
  292  	}
  293  
  294: 	while (hrt_elapsed_time(&_doors_opened) < 500 * 1000 && hrt_elapsed_time(&starttime) < 2000000) {
  295  		px4_usleep(50000);
  296  		warnx("delayed by door!");
  ...
  702  
  703  				/* 2s after drop, reset and close everything again */
  704: 				if ((hrt_elapsed_time(&_doors_opened) > 2 * 1000 * 1000)) {
  705  					_drop_state = DROP_STATE_INIT;
  706  					_drop_approval = false;
  ...
  731  			px4_usleep(sleeptime_us);
  732  
  733: 			dt_runs = hrt_elapsed_time(&last_run) / 1e6f;
  734  			last_run = hrt_absolute_time();
  735  		}

/Users/lorenzmeier/src/Firmware/src/lib/CollisionPrevention/CollisionPrevention.cpp:
  110  	const obstacle_distance_s &obstacle_distance = _sub_obstacle_distance->get();
  111  
  112: 	if (hrt_elapsed_time(&obstacle_distance.timestamp) < RANGE_STREAM_TIMEOUT_US) {
  113  		float max_detection_distance = obstacle_distance.max_distance / 100.0f; //convert to meters
  114  

/Users/lorenzmeier/src/Firmware/src/lib/parameters/parameters.cpp:
  656  
  657  	static constexpr const hrt_abstime rate_limit = 2_s; // rate-limit saving to 2 seconds
  658: 	const hrt_abstime last_save_elapsed = hrt_elapsed_time(&last_autosave_timestamp);
  659  
  660  	if (last_save_elapsed < rate_limit && rate_limit > last_save_elapsed + delay) {
  ...
 1396  
 1397  	if (!autosave_disabled && (last_autosave_timestamp > 0)) {
 1398: 		PX4_INFO("last auto save: %.3f seconds ago", hrt_elapsed_time(&last_autosave_timestamp) * 1e-6);
 1399  	}
 1400  

/Users/lorenzmeier/src/Firmware/src/lib/parameters/parameters_shmem.cpp:
  715  
  716  	const hrt_abstime rate_limit = 2000 * 1000; // rate-limit saving to 2 seconds
  717: 	hrt_abstime last_save_elapsed = hrt_elapsed_time(&last_autosave_timestamp);
  718  
  719  	if (last_save_elapsed < rate_limit && rate_limit > last_save_elapsed + delay) {
  ...
 1502  
 1503  	if (!autosave_disabled && (last_autosave_timestamp > 0)) {
 1504: 		PX4_INFO("last auto save: %.3f seconds ago", hrt_elapsed_time(&last_autosave_timestamp) * 1e-6);
 1505  	}
 1506  

/Users/lorenzmeier/src/Firmware/src/lib/pwm_limit/pwm_limit.cpp:
   73  			}
   74  
   75: 			if (hrt_elapsed_time(&limit->time_armed) >= INIT_TIME_US) {
   76  				limit->state = PWM_LIMIT_STATE_OFF;
   77  			}
   ..
   94  			limit->state = PWM_LIMIT_STATE_OFF;
   95  
   96: 		} else if (hrt_elapsed_time(&limit->time_armed) >= RAMP_TIME_US) {
   97  			limit->state = PWM_LIMIT_STATE_ON;
   98  		}
   ..
  137  
  138  	case PWM_LIMIT_STATE_RAMP: {
  139: 			hrt_abstime diff = hrt_elapsed_time(&limit->time_armed);
  140  
  141  			progress = diff * PROGRESS_INT_SCALING / RAMP_TIME_US;

/Users/lorenzmeier/src/Firmware/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp:
  368  					if (_ext_hdg_mode == 1) {
  369  						// Check for timeouts on data
  370: 						_ext_hdg_good = vision.timestamp > 0 && (hrt_elapsed_time(&vision.timestamp) < 500000);
  371  					}
  372  				}
  ...
  400  					if (_ext_hdg_mode == 2) {
  401  						// Check for timeouts on data
  402: 						_ext_hdg_good = mocap.timestamp > 0 && (hrt_elapsed_time(&mocap.timestamp) < 500000);
  403  					}
  404  				}
  ...
  413  
  414  			if (orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &gpos) == PX4_OK) {
  415: 				if (_mag_decl_auto && gpos.eph < 20.0f && hrt_elapsed_time(&gpos.timestamp) < 1000000) {
  416  					/* set magnetic declination automatically */
  417  					update_mag_declination(math::radians(get_mag_declination(gpos.lat, gpos.lon)));

/Users/lorenzmeier/src/Firmware/src/modules/commander/accelerometer_calibration.cpp:
  838  	hrt_abstime start = hrt_absolute_time();
  839  
  840: 	while (hrt_elapsed_time(&start) < settle_time * 1000000) {
  841  		calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG,
  842: 				     (int)(90 * hrt_elapsed_time(&start) / 1e6f / (float)settle_time));
  843  		px4_sleep(settle_time / 10);
  844  	}
  ...
  847  
  848  	// average attitude for 5 seconds
  849: 	while (hrt_elapsed_time(&start) < cal_time * 1000000) {
  850  		int pollret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
  851  

/Users/lorenzmeier/src/Firmware/src/modules/commander/Commander.cpp:
  552  					     &status_flags,
  553  					     arm_requirements,
  554: 					     hrt_elapsed_time(&commander_boot_timestamp));
  555  
  556  	if (arming_res == TRANSITION_CHANGED) {
  ...
 1613  			orb_copy(ORB_ID(system_power), system_power_sub, &system_power);
 1614  
 1615: 			if (hrt_elapsed_time(&system_power.timestamp) < 200_ms) {
 1616  				if (system_power.servo_valid &&
 1617  				    !system_power.brick_valid &&
 ....
 1651  					if (TRANSITION_CHANGED == arming_state_transition(&status, safety, vehicle_status_s::ARMING_STATE_STANDBY,
 1652  							&armed, true /* fRunPreArmChecks */, &mavlink_log_pub,
 1653: 							&status_flags, arm_requirements, hrt_elapsed_time(&commander_boot_timestamp))
 1654  					   ) {
 1655  						status_changed = true;
 ....
 1806  			arming_ret = arming_state_transition(&status, safety, vehicle_status_s::ARMING_STATE_STANDBY, &armed,
 1807  							     true /* fRunPreArmChecks */, &mavlink_log_pub, &status_flags,
 1808: 							     arm_requirements, hrt_elapsed_time(&commander_boot_timestamp));
 1809  
 1810  			if (arming_ret == TRANSITION_DENIED) {
 ....
 1875  				const hrt_abstime geofence_violation_action_interval = 10_s;
 1876  
 1877: 				if (hrt_elapsed_time(&last_geofence_violation) > geofence_violation_action_interval) {
 1878  
 1879  					last_geofence_violation = hrt_absolute_time();
 ....
 1998  		/* RC input check */
 1999  		if (!status_flags.rc_input_blocked && sp_man.timestamp != 0 &&
 2000: 		    (hrt_elapsed_time(&sp_man.timestamp) < (rc_loss_timeout * 1_s))) {
 2001  
 2002  			/* handle the case where RC signal was regained */
 ....
 2010  				if (status.rc_signal_lost) {
 2011  					mavlink_log_info(&mavlink_log_pub, "MANUAL CONTROL REGAINED after %llums",
 2012: 							 hrt_elapsed_time(&rc_signal_lost_timestamp) / 1000);
 2013  					set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_RCRECEIVER, true, true, true
 2014  							 && status_flags.rc_calibration_valid, status);
 ....
 2050  					arming_ret = arming_state_transition(&status, safety, vehicle_status_s::ARMING_STATE_STANDBY, &armed,
 2051  									     true /* fRunPreArmChecks */,
 2052: 									     &mavlink_log_pub, &status_flags, arm_requirements, hrt_elapsed_time(&commander_boot_timestamp));
 2053  				}
 2054  
 ....
 2068  			/* allow a grace period for re-arming: preflight checks don't need to pass during that time,
 2069  			 * for example for accidential in-air disarming */
 2070: 			const bool in_arming_grace_period = last_disarmed_timestamp != 0 && hrt_elapsed_time(&last_disarmed_timestamp) < 5_s;
 2071  			const bool arm_switch_to_arm_transition = arm_switch_is_button == 0 &&
 2072  					_last_sp_man_arm_switch == manual_control_setpoint_s::SWITCH_POS_OFF &&
 ....
 2100  						arming_ret = arming_state_transition(&status, safety, vehicle_status_s::ARMING_STATE_ARMED, &armed,
 2101  										     !in_arming_grace_period /* fRunPreArmChecks */,
 2102: 										     &mavlink_log_pub, &status_flags, arm_requirements, hrt_elapsed_time(&commander_boot_timestamp));
 2103  
 2104  						if (arming_ret != TRANSITION_CHANGED) {
 ....
 2198  				    || status.engine_failure) {
 2199  
 2200: 					const float elapsed = hrt_elapsed_time(&timestamp_engine_healthy) / 1e6f;
 2201  
 2202  					/* potential failure, measure time */
 ....
 2360  			if (armed.armed) {
 2361  				if ((!was_armed || (was_landed && !land_detector.landed)) &&
 2362: 				    (hrt_elapsed_time(&commander_boot_timestamp) > INAIR_RESTART_HOLDOFF_INTERVAL)) {
 2363  
 2364  					/* update home position on arming if at least 500 ms from commander start spent to avoid setting home on in-air restart */
 ....
 2440  
 2441  		/* publish states (armed, control_mode, vehicle_status, commander_state, vehicle_status_flags) at 1 Hz or immediately when changed */
 2442: 		if (hrt_elapsed_time(&status.timestamp) >= 1_s || status_changed || nav_state_changed) {
 2443  
 2444  			set_control_mode();
 ....
 2462  				 * when the rest of the system is fully initialized)
 2463  				 */
 2464: 				armed.prearmed = (hrt_elapsed_time(&commander_boot_timestamp) > 5_s);
 2465  			}
 2466  
 ....
 2523  
 2524  		/* play sensor failure tunes if we already waited for hotplug sensors to come up and failed */
 2525: 		status_flags.condition_system_hotplug_timeout = (hrt_elapsed_time(&commander_boot_timestamp) > HOTPLUG_SENS_TIMEOUT);
 2526  
 2527  		if (!sensor_fail_tune_played && (!status_flags.condition_system_sensors_initialized
 ....
 2637  
 2638  		/* set mode */
 2639: 		if (overload && (hrt_elapsed_time(&overload_start) > overload_warn_delay)) {
 2640  			led_mode = led_control_s::MODE_BLINK_FAST;
 2641  			led_color = led_control_s::COLOR_PURPLE;
 ....
 3179  	}
 3180  
 3181: 	const bool data_stale = ((hrt_elapsed_time(&data_timestamp_us) > _failsafe_pos_delay.get() * 1_s)
 3182  				 || (data_timestamp_us == 0));
 3183  	const float req_accuracy = (was_valid ? required_accuracy * 2.5f : required_accuracy);
 ....
 3189  		if (was_valid) {
 3190  			// still valid, continue to decrease probation time
 3191: 			const int64_t probation_time_new = *probation_time_us - hrt_elapsed_time(last_fail_time_us);
 3192  			*probation_time_us = math::constrain(probation_time_new, POSVEL_PROBATION_MIN, POSVEL_PROBATION_MAX);
 3193  
 3194  		} else {
 3195  			// check if probation period has elapsed
 3196: 			if (hrt_elapsed_time(last_fail_time_us) > *probation_time_us) {
 3197  				valid = true;
 3198  			}
 ....
 3207  		} else {
 3208  			// failed again, increase probation time
 3209: 			const int64_t probation_time_new = *probation_time_us + hrt_elapsed_time(last_fail_time_us) * _failsafe_pos_gain.get();
 3210  			*probation_time_us = math::constrain(probation_time_new, POSVEL_PROBATION_MIN, POSVEL_PROBATION_MAX);
 3211  		}
 ....
 3608  					if (TRANSITION_DENIED == arming_state_transition(&status, safety, vehicle_status_s::ARMING_STATE_INIT, &armed,
 3609  							false /* fRunPreArmChecks */, &mavlink_log_pub, &status_flags,
 3610: 							arm_requirements, hrt_elapsed_time(&commander_boot_timestamp))) {
 3611  
 3612  						answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED, command_ack_pub);
 ....
 3696  						arming_state_transition(&status, safety, vehicle_status_s::ARMING_STATE_STANDBY, &armed,
 3697  									false /* fRunPreArmChecks */,
 3698: 									&mavlink_log_pub, &status_flags, arm_requirements, hrt_elapsed_time(&commander_boot_timestamp));
 3699  
 3700  					} else {
 ....
 3870  
 3871  	bool success = Preflight::preflightCheck(&mavlink_log_pub, status, status_flags, checkGNSS, report, false,
 3872: 			hrt_elapsed_time(&commander_boot_timestamp));
 3873  
 3874  	if (success) {
 ....
 3897  			/* perform system checks when new telemetry link connected */
 3898  			if (/* we first connect a link or re-connect a link after loosing it or haven't yet reported anything */
 3899: 				(_telemetry[i].last_heartbeat == 0 || (hrt_elapsed_time(&_telemetry[i].last_heartbeat) > 3_s)
 3900  				 || !_telemetry[i].preflight_checks_reported) &&
 3901  				/* and this link has a communication partner */
 3902  				(telemetry.heartbeat_time > 0) &&
 3903  				/* and it is still connected */
 3904: 				(hrt_elapsed_time(&telemetry.heartbeat_time) < 2_s) &&
 3905  				/* and the system is not already armed (and potentially flying) */
 3906  				!armed.armed) {
 ....
 3986  
 3987  		if (_telemetry[i].last_heartbeat != 0 &&
 3988: 		    hrt_elapsed_time(&_telemetry[i].last_heartbeat) < dl_loss_timeout_local * 1e6) {
 3989  			/* handle the case where data link was gained first time or regained,
 3990  			 * accept datalink as healthy only after datalink_regain_timeout seconds
 3991  			 * */
 3992  			if (_telemetry[i].lost &&
 3993: 			    hrt_elapsed_time(&_telemetry[i].last_dl_loss) > dl_regain_timeout_local * 1e6) {
 3994  
 3995  				/* report a regain */
 ....
 4093  		if (orb_copy(ORB_ID(battery_status), _battery_sub, &battery) == PX4_OK) {
 4094  
 4095: 			if ((hrt_elapsed_time(&battery.timestamp) < 5_s)
 4096  			    && battery.connected
 4097  			    && (_battery_warning == battery_status_s::BATTERY_WARNING_NONE)) {
 ....
 4194  			} else {
 4195  				// if nav status is unconfirmed, confirm yaw angle as passed after 30 seconds or achieving 5 m/s of speed
 4196: 				const bool sufficient_time = (hrt_elapsed_time(&_time_at_takeoff) > 30_s);
 4197  				const bool sufficient_speed = (lpos.vx * lpos.vx + lpos.vy * lpos.vy > 25.0f);
 4198  
 ....
 4212  
 4213  						// if the innovation test has failed continuously, declare the nav as failed
 4214: 						if (hrt_elapsed_time(&_time_last_innov_pass) > 1_s) {
 4215  							_nav_test_failed = true;
 4216  							mavlink_log_emergency(&mavlink_log_pub, "CRITICAL NAVIGATION FAILURE - CHECK SENSOR CALIBRATION");

/Users/lorenzmeier/src/Firmware/src/modules/commander/esc_calibration.cpp:
  164  		hrt_abstime timeout_wait = batt_connected ? pwm_high_timeout : battery_connect_wait_timeout;
  165  
  166: 		if (hrt_elapsed_time(&timeout_start) > timeout_wait) {
  167  			if (!batt_connected) {
  168  				calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Timeout waiting for battery");

/Users/lorenzmeier/src/Firmware/src/modules/commander/PreflightCheck.cpp:
  110  		uORB::Subscription<sensor_mag_s> magnetometer{ORB_ID(sensor_mag), 0, instance};
  111  
  112: 		mag_valid = (hrt_elapsed_time(&magnetometer.get().timestamp) < 1_s);
  113  
  114  		if (!mag_valid) {
  ...
  246  		uORB::Subscription<sensor_accel_s> accel{ORB_ID(sensor_accel), 0, instance};
  247  
  248: 		accel_valid = (hrt_elapsed_time(&accel.get().timestamp) < 1_s);
  249  
  250  		if (!accel_valid) {
  ...
  310  		uORB::Subscription<sensor_gyro_s> gyro{ORB_ID(sensor_gyro), 0, instance};
  311  
  312: 		gyro_valid = (hrt_elapsed_time(&gyro.get().timestamp) < 1_s);
  313  
  314  		if (!gyro_valid) {
  ...
  353  		uORB::Subscription<sensor_baro_s> baro{ORB_ID(sensor_baro), 0, instance};
  354  
  355: 		baro_valid = (hrt_elapsed_time(&baro.get().timestamp) < 1_s);
  356  
  357  		if (!baro_valid) {
  ...
  388  
  389  	if ((orb_copy(ORB_ID(differential_pressure), fd_diffpres, &differential_pressure) != PX4_OK) ||
  390: 	    (hrt_elapsed_time(&differential_pressure.timestamp) > 1_s)) {
  391  		if (report_fail && !optional) {
  392  			mavlink_log_critical(mavlink_log_pub, "Preflight Fail: Airspeed Sensor missing");
  ...
  399  
  400  	if ((orb_copy(ORB_ID(airspeed), fd_airspeed, &airspeed) != PX4_OK) ||
  401: 	    (hrt_elapsed_time(&airspeed.timestamp) > 1_s)) {
  402  		if (report_fail && !optional) {
  403  			mavlink_log_critical(mavlink_log_pub, "Preflight Fail: Airspeed Sensor missing");
  ...
  464  		if (orb_copy(ORB_ID(system_power), system_power_sub, &system_power) == PX4_OK) {
  465  
  466: 			if (hrt_elapsed_time(&system_power.timestamp) < 200_ms) {
  467  
  468  				/* copy avionics voltage */

/Users/lorenzmeier/src/Firmware/src/modules/commander/state_machine_helper.cpp:
  144  		    && !hil_enabled) {
  145  
  146: 			if ((last_preflight_check == 0) || (hrt_elapsed_time(&last_preflight_check) > 1000 * 1000)) {
  147  
  148  				status_flags->condition_system_sensors_initialized = Preflight::preflightCheck(mavlink_log_pub, *status, *status_flags,

/Users/lorenzmeier/src/Firmware/src/modules/fw_att_control/FixedwingAttitudeControl.cpp:
  471  	const bool airspeed_valid = PX4_ISFINITE(_airspeed_sub.get().indicated_airspeed_m_s)
  472  				    && (_airspeed_sub.get().indicated_airspeed_m_s > 0.0f)
  473: 				    && (hrt_elapsed_time(&_airspeed_sub.get().timestamp) < 1e6);
  474  
  475  	if (!_parameters.airspeed_disabled && airspeed_valid) {

/Users/lorenzmeier/src/Firmware/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp:
  395  	} else {
  396  		// no airspeed updates for one second
  397: 		if (airspeed_valid && (hrt_elapsed_time(&_airspeed_last_valid) > 1_s)) {
  398  			airspeed_valid = false;
  399  		}
  ...
  778  	const hrt_abstime delta_takeoff = 10_s;
  779  
  780: 	return (hrt_elapsed_time(&_time_went_in_air) < delta_takeoff)
  781  	       && (_global_pos.alt <= _takeoff_ground_alt + _parameters.climbout_diff);
  782  }
  ...
  802  
  803  	if (_control_position_last_called > 0) {
  804: 		dt = hrt_elapsed_time(&_control_position_last_called) * 1e-6f;
  805  	}
  806  
  ...
 1332  
 1333  				/* Inform user that launchdetection is running every 4s */
 1334: 				if (hrt_elapsed_time(&_launch_detection_notify) > 4e6) {
 1335  					mavlink_log_critical(&_mavlink_log_pub, "Launch detection running");
 1336  					_launch_detection_notify = hrt_absolute_time();
 ....
 1535  			// wait for some time, maybe we will soon get a valid estimate
 1536  			// until then just use the altitude of the landing waypoint
 1537: 			if (hrt_elapsed_time(&_time_started_landing) < 10_s) {
 1538  				terrain_alt = pos_sp_curr.alt;
 1539  
 ....
 1544  			}
 1545  
 1546: 		} else if ((!_global_pos.terrain_alt_valid && hrt_elapsed_time(&_time_last_t_alt) < T_ALT_TIMEOUT)
 1547  			   || _land_noreturn_vertical) {
 1548  			// use previous terrain estimate for some time and hope to recover
 ....
 1918  
 1919  	if (_last_tecs_update > 0) {
 1920: 		dt = hrt_elapsed_time(&_last_tecs_update) * 1e-6;
 1921  	}
 1922  

/Users/lorenzmeier/src/Firmware/src/modules/fw_pos_control_l1/launchdetection/CatapultLaunchMethod.cpp:
   55  void CatapultLaunchMethod::update(float accel_x)
   56  {
   57: 	float dt = hrt_elapsed_time(&_last_timestamp) * 1e-6f;
   58  	_last_timestamp = hrt_absolute_time();
   59  

/Users/lorenzmeier/src/Firmware/src/modules/fw_pos_control_l1/runway_takeoff/RunwayTakeoff.cpp:
   80  	switch (_state) {
   81  	case RunwayTakeoffState::THROTTLE_RAMP:
   82: 		if (hrt_elapsed_time(&_initialized_time) > _throttle_ramp_time) {
   83  			_state = RunwayTakeoffState::CLAMPED_TO_RUNWAY;
   84  		}
   ..
  196  	switch (_state) {
  197  	case RunwayTakeoffState::THROTTLE_RAMP: {
  198: 			float throttle = hrt_elapsed_time(&_initialized_time) / (float)_throttle_ramp_time *
  199  					 _takeoff_throttle.get();
  200  			return throttle < _takeoff_throttle.get() ?

/Users/lorenzmeier/src/Firmware/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp:
  194  
  195  	if (_control_position_last_called > 0) {
  196: 		dt = hrt_elapsed_time(&_control_position_last_called) * 1e-6f;
  197  	}
  198  

/Users/lorenzmeier/src/Firmware/src/modules/land_detector/FixedwingLandDetector.cpp:
  102  	bool landDetected = false;
  103  
  104: 	if (hrt_elapsed_time(&_local_pos.timestamp) < 500 * 1000) {
  105  
  106  		// horizontal velocity

/Users/lorenzmeier/src/Firmware/src/modules/land_detector/LandDetector.cpp:
  128  
  129  	// publish at 1 Hz, very first time, or when the result has changed
  130: 	if ((hrt_elapsed_time(&_landDetected.timestamp) >= 1_s) ||
  131  	    (_landDetectedPub == nullptr) ||
  132  	    (_landDetected.landed != landDetected) ||

/Users/lorenzmeier/src/Firmware/src/modules/land_detector/MulticopterLandDetector.cpp:
  165  	bool verticalMovement;
  166  
  167: 	if (hrt_elapsed_time(&_landed_time) < LAND_DETECTOR_LAND_PHASE_TIME_US) {
  168  
  169  		// Widen acceptance thresholds for landed state right after arming
  ...
  220  
  221  	// Widen acceptance thresholds for landed state right after landed
  222: 	if (hrt_elapsed_time(&_landed_time) < LAND_DETECTOR_LAND_PHASE_TIME_US) {
  223  		landThresholdFactor = 2.5f;
  224  	}
  ...
  237  		// falling consider it to be landed. This should even sustain
  238  		// quite acrobatic flight.
  239: 		return (_min_trust_start > 0) && (hrt_elapsed_time(&_min_trust_start) > 8_s);
  240  	}
  241  
  ...
  295  {
  296  	return _vehicleLocalPosition.timestamp != 0 &&
  297: 	       hrt_elapsed_time(&_vehicleLocalPosition.timestamp) < 500_ms &&
  298  	       _vehicleLocalPosition.z_valid;
  299  }
  ...
  307  {
  308  	bool has_updated = (_vehicleLocalPositionSetpoint.timestamp != 0)
  309: 			   && (hrt_elapsed_time(&_vehicleLocalPositionSetpoint.timestamp) < 500_ms);
  310  
  311  	return (_control_mode.flag_control_climb_rate_enabled && has_updated && PX4_ISFINITE(_vehicleLocalPositionSetpoint.vz));

/Users/lorenzmeier/src/Firmware/src/modules/land_detector/VtolLandDetector.cpp:
   89  
   90  	// for vtol we additionally consider airspeed
   91: 	if (hrt_elapsed_time(&_airspeed.timestamp) < 500 * 1000 && _airspeed.confidence > 0.99f
   92  	    && PX4_ISFINITE(_airspeed.indicated_airspeed_m_s)) {
   93  

/Users/lorenzmeier/src/Firmware/src/modules/load_mon/load_mon.cpp:
  196  	/* compute system load */
  197  	const hrt_abstime total_runtime = system_load.tasks[0].total_runtime;
  198: 	const hrt_abstime interval = hrt_elapsed_time(&_last_idle_time_sample);
  199  	const hrt_abstime interval_idletime = total_runtime - _last_idle_time;
  200  

/Users/lorenzmeier/src/Firmware/src/modules/logger/log_writer_file.cpp:
  351  		//write dropout msg
  352  		ulog_message_dropout_s dropout_msg;
  353: 		dropout_msg.duration = (uint16_t)(hrt_elapsed_time(&dropout_start) / 1000);
  354  		_buffers[(int)type].write_no_check(&dropout_msg, sizeof(dropout_msg));
  355  	}

/Users/lorenzmeier/src/Firmware/src/modules/logger/log_writer_mavlink.cpp:
  184  				break;
  185  			}
  186: 		} while (!got_ack && hrt_elapsed_time(&started) / 1000 < timeout_ms);
  187  
  188  		if (!got_ack) {
  ...
  192  		}
  193  
  194: 		PX4_DEBUG("got ack in %i ms", (int)(hrt_elapsed_time(&started) / 1000));
  195  	}
  196  

/Users/lorenzmeier/src/Firmware/src/modules/logger/logger.cpp:
 1393  
 1394  		if (stats.dropout_start) {
 1395: 			float dropout_duration = (float)(hrt_elapsed_time(&stats.dropout_start) / 1000) / 1.e3f;
 1396  
 1397  			if (dropout_duration > stats.max_dropout_duration) {

/Users/lorenzmeier/src/Firmware/src/modules/mavlink/mavlink_command_sender.cpp:
  143  
  144  	while (command_item_t *item = _commands.get_next()) {
  145: 		if (hrt_elapsed_time(&item->last_time_sent_us) <= TIMEOUT_US) {
  146  			// We keep waiting for the timeout.
  147  			continue;

/Users/lorenzmeier/src/Firmware/src/modules/mavlink/mavlink_ftp.cpp:
  962  	if (_work_buffer1 || _work_buffer2) {
  963  		// free the work buffers if they are not used for a while
  964: 		if (hrt_elapsed_time(&_last_work_buffer_access) > 2000000) {
  965  			if (_work_buffer1) {
  966  				delete[] _work_buffer1;

/Users/lorenzmeier/src/Firmware/src/modules/mavlink/mavlink_main.cpp:
  854  			 */
  855  			if (_last_write_try_time != 0 &&
  856: 			    hrt_elapsed_time(&_last_write_success_time) > 500_ms &&
  857  			    _last_write_success_time != _last_write_try_time) {
  858  
  ...
  894  		if ((_mode != MAVLINK_MODE_ONBOARD) && broadcast_enabled() &&
  895  		    (!get_client_source_initialized()
  896: 		     || (hrt_elapsed_time(&_tstatus.heartbeat_time) > 3_s))) {
  897  
  898  			if (!_broadcast_address_found) {
  ...
 1631  
 1632  		// check for RADIO_STATUS timeout and reset
 1633: 		if (hrt_elapsed_time(&_rstatus.timestamp) > 5_s) {
 1634  			PX4_ERR("instance %d: RADIO_STATUS timeout", _instance_id);
 1635  			set_telemetry_status_type(telemetry_status_s::TELEMETRY_STATUS_RADIO_TYPE_GENERIC);
 ....
 2518  
 2519  		// publish status at 1 Hz, or sooner if HEARTBEAT has updated
 2520: 		if ((hrt_elapsed_time(&_tstatus.timestamp) >= 1_s) || (_tstatus.timestamp < _tstatus.heartbeat_time)) {
 2521  			publish_telemetry_status();
 2522  		}
 ....
 2748  {
 2749  	if (_tstatus.heartbeat_time > 0) {
 2750: 		printf("\tGCS heartbeat:\t%llu us ago\n", (unsigned long long)hrt_elapsed_time(&_tstatus.heartbeat_time));
 2751  	}
 2752  

/Users/lorenzmeier/src/Firmware/src/modules/mavlink/mavlink_main.h:
  242  	bool			get_forwarding_on() { return _forwarding_on; }
  243  
  244: 	bool			is_connected() { return (hrt_elapsed_time(&_tstatus.heartbeat_time) < 3_s); }
  245  
  246  	bool			broadcast_enabled() { return _param_broadcast_mode.get() == BROADCAST_MODE_ON; }

/Users/lorenzmeier/src/Firmware/src/modules/mavlink/mavlink_messages.cpp:
 4429  		// local position timeout after 10 ms
 4430  		// avoid publishing only baro altitude_monotonic if possible
 4431: 		bool lpos_timeout = (hrt_elapsed_time(&_local_pos_time) > 10000);
 4432  
 4433  		if (lpos_updated || (air_data_updated && lpos_timeout)) {

/Users/lorenzmeier/src/Firmware/src/modules/mavlink/mavlink_mission.cpp:
  532  	/* check for timed-out operations */
  533  	if (_state == MAVLINK_WPM_STATE_GETLIST && (_time_last_sent > 0)
  534: 	    && hrt_elapsed_time(&_time_last_sent) > MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT) {
  535  
  536  		// try to request item again after timeout
  ...
  538  
  539  	} else if (_state != MAVLINK_WPM_STATE_IDLE && (_time_last_recv > 0)
  540: 		   && hrt_elapsed_time(&_time_last_recv) > MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT) {
  541  
  542  		_mavlink->send_statustext_critical("Operation timeout");

/Users/lorenzmeier/src/Firmware/src/modules/mavlink/mavlink_receiver.cpp:
 2689  				hrt_abstime stime = _mavlink->get_start_time();
 2690  
 2691: 				if ((stime != 0 && (hrt_elapsed_time(&stime) > 3 * 1000 * 1000))
 2692  				    || (srcaddr_last.sin_addr.s_addr == htonl(localhost))) {
 2693  					srcaddr_last.sin_addr.s_addr = srcaddr.sin_addr.s_addr;

/Users/lorenzmeier/src/Firmware/src/modules/mavlink/mavlink_ulog.cpp:
  105  
  106  	if (_waiting_for_initial_ack) {
  107: 		if (hrt_elapsed_time(&_last_sent_time) > 3e5) {
  108  			PX4_WARN("no ack from logger (is it running?)");
  109  			return -1;
  ...
  123  		} else {
  124  
  125: 			if (hrt_elapsed_time(&_last_sent_time) > ulog_stream_ack_s::ACK_TIMEOUT * 1000) {
  126  				if (++_sent_tries > ulog_stream_ack_s::ACK_MAX_TRIES) {
  127  					return -ETIMEDOUT;

/Users/lorenzmeier/src/Firmware/src/modules/mc_pos_control/mc_pos_control_main.cpp:
 1213  {
 1214  	if (MPC_OBS_AVOID.get()) {
 1215: 		const bool avoidance_data_timeout = hrt_elapsed_time((hrt_abstime *)&_traj_wp_avoidance.timestamp) > TRAJECTORY_STREAM_TIMEOUT_US;
 1216  		const bool avoidance_point_valid = _traj_wp_avoidance.waypoints[vehicle_trajectory_waypoint_s::POINT_0].point_valid == true;
 1217  		const bool in_mission = _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION;

/Users/lorenzmeier/src/Firmware/src/modules/navigator/geofence.cpp:
  238  
  239  		if (max_vertical_distance > FLT_EPSILON && (dist_z > max_vertical_distance)) {
  240: 			if (hrt_elapsed_time(&_last_vertical_range_warning) > GEOFENCE_RANGE_WARNING_LIMIT) {
  241  				mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Maximum altitude above home exceeded by %.1f m",
  242  						     (double)(dist_z - max_vertical_distance));
  ...
  248  
  249  		if (max_horizontal_distance > FLT_EPSILON && (dist_xy > max_horizontal_distance)) {
  250: 			if (hrt_elapsed_time(&_last_horizontal_range_warning) > GEOFENCE_RANGE_WARNING_LIMIT) {
  251  				mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Maximum distance from home exceeded by %.1f m",
  252  						     (double)(dist_xy - max_horizontal_distance));

/Users/lorenzmeier/src/Firmware/src/modules/navigator/gpsfailure.cpp:
  105  			/* Measure time */
  106  			if ((_param_loitertime.get() > FLT_EPSILON) &&
  107: 			    (hrt_elapsed_time(&_timestamp_activation) > _param_loitertime.get() * 1e6f)) {
  108  				/* no recovery, advance the state machine */
  109  				PX4_WARN("GPS not recovered, switching to next failure state");

/Users/lorenzmeier/src/Firmware/src/modules/navigator/navigator_main.cpp:
  526  		if (have_geofence_position_data &&
  527  		    (_geofence.getGeofenceAction() != geofence_result_s::GF_ACTION_NONE) &&
  528: 		    (hrt_elapsed_time(&last_geofence_check) > GEOFENCE_CHECK_INTERVAL)) {
  529  
  530  			bool inside = _geofence.check(_global_pos, _gps_pos, _home_pos,

/Users/lorenzmeier/src/Firmware/src/modules/navigator/precland.cpp:
  116  	}
  117  
  118: 	if ((hrt_elapsed_time(&_target_pose.timestamp) / 1e6f) > _param_timeout.get()) {
  119  		_target_pose_valid = false;
  120  	}

/Users/lorenzmeier/src/Firmware/src/modules/px4iofirmware/adc.c:
  154  
  155  		/* never spin forever - this will give a bogus result though */
  156: 		if (hrt_elapsed_time(&now) > 100) {
  157  			perf_end(adc_perf);
  158  			return 0xffff;

/Users/lorenzmeier/src/Firmware/src/modules/px4iofirmware/controls.c:
  461  	 * have lost input.
  462  	 */
  463: 	if (!rc_input_lost && hrt_elapsed_time(&system_state.rc_channels_timestamp_received) > 200000) {
  464  		rc_input_lost = true;
  465  
  ...
  575  	 * and then invalidate it.
  576  	 */
  577: 	if (hrt_elapsed_time(&ppm_last_valid_decode) < 200000) {
  578  
  579  		/* PPM data exists, copy it */

/Users/lorenzmeier/src/Firmware/src/modules/px4iofirmware/mixer.cpp:
  120  	/* check that we are receiving fresh data from the FMU */
  121  	if ((system_state.fmu_data_received_time == 0) ||
  122: 	    hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {
  123  
  124  		/* too long without FMU input, time to go to failsafe */

/Users/lorenzmeier/src/Firmware/src/modules/replay/replay_main.cpp:
  844  	if (!should_exit()) {
  845  		PX4_INFO("Replay done (published %u msgs, %.3lf s)", nr_published_messages,
  846: 			 (double)hrt_elapsed_time(&_replay_start_time) / 1.e6);
  847  
  848  		//TODO: should we close the log file & exit (optionally, by adding a parameter -q) ?

/Users/lorenzmeier/src/Firmware/src/modules/sensors/rc_update.cpp:
  466  
  467  			/* Update parameters from RC Channels (tuning with RC) if activated */
  468: 			if (hrt_elapsed_time(&_last_rc_to_param_map_time) > 1e6) {
  469  				set_params_from_rc(parameter_handles);
  470  				_last_rc_to_param_map_time = hrt_absolute_time();

/Users/lorenzmeier/src/Firmware/src/modules/sensors/sensors.cpp:
  696  		 * when not adding sensors poll for param updates
  697  		 */
  698: 		if (!_armed && hrt_elapsed_time(&last_config_update) > 500_ms) {
  699  			_voted_sensors_update.initialize_sensors();
  700  			last_config_update = hrt_absolute_time();

/Users/lorenzmeier/src/Firmware/src/modules/simulator/simulator_mavlink.cpp:
  317  
  318  			// battery simulation (limit update to 100Hz)
  319: 			if (hrt_elapsed_time(&_battery_status.timestamp) >= 10000) {
  320  
  321  				const float discharge_interval_us = _battery_drain_interval_s.get() * 1000 * 1000;

/Users/lorenzmeier/src/Firmware/src/modules/systemlib/hysteresis/hysteresis.cpp:
   67  	if (_requested_state != _state) {
   68  
   69: 		if (hrt_elapsed_time(&_last_time_to_change_state) >= (_state ?
   70  				_hysteresis_time_from_true_us :
   71  				_hysteresis_time_from_false_us)) {

/Users/lorenzmeier/src/Firmware/src/modules/uORB/uORB_tests/uORBTest_UnitTest.cpp:
  122  		current_value = t.val;
  123  
  124: 		unsigned elt = (unsigned)hrt_elapsed_time(&t.time);
  125  		latency_integral += elt;
  126  		timings[i] = elt;

/Users/lorenzmeier/src/Firmware/src/platforms/posix/drivers/df_lsm9ds1_wrapper/df_lsm9ds1_wrapper.cpp:
  712  
  713  		// Report every 5s.
  714: 		const bool due_to_report = (hrt_elapsed_time(&_last_accel_range_hit_time) > 5000000);
  715  
  716  		if (threshold_reached && due_to_report) {

/Users/lorenzmeier/src/Firmware/src/platforms/posix/drivers/df_mpu6050_wrapper/df_mpu6050_wrapper.cpp:
  557  
  558  		// Report every 5s.
  559: 		const bool due_to_report = (hrt_elapsed_time(&_last_accel_range_hit_time) > 5000000);
  560  
  561  		if (threshold_reached && due_to_report) {

/Users/lorenzmeier/src/Firmware/src/platforms/posix/drivers/df_mpu9250_wrapper/df_mpu9250_wrapper.cpp:
  764  
  765  		// Report every 5s.
  766: 		const bool due_to_report = (hrt_elapsed_time(&_last_accel_range_hit_time) > 5000000);
  767  
  768  		if (threshold_reached && due_to_report) {

/Users/lorenzmeier/src/Firmware/src/systemcmds/motor_ramp/motor_ramp.cpp:
  344  
  345  		if (last_run > 0) {
  346: 			dt = hrt_elapsed_time(&last_run) * 1e-6;
  347  
  348  		} else {
  ...
  351  
  352  		last_run = hrt_absolute_time();
  353: 		timer = hrt_elapsed_time(&start) * 1e-6;
  354  
  355  		switch (ramp_state) {

/Users/lorenzmeier/src/Firmware/src/systemcmds/sd_bench/sd_bench.c:
  158  	hrt_abstime fsync_start = hrt_absolute_time();
  159  	fsync(fd);
  160: 	return hrt_elapsed_time(&fsync_start) / 1000;
  161  }
  162  
  ...
  174  		unsigned int fsync_time = 0;
  175  
  176: 		while ((int64_t)hrt_elapsed_time(&start) < run_duration * 1000) {
  177  
  178  			hrt_abstime write_start = hrt_absolute_time();
  179  			size_t written = write(fd, block, block_size);
  180: 			unsigned int write_time = hrt_elapsed_time(&write_start) / 1000;
  181  
  182  			if (write_time > max_write_time) {
  ...
  202  
  203  		//report
  204: 		double elapsed = hrt_elapsed_time(&start) / 1.e6;
  205  		PX4_INFO("  Run %2i: %8.2lf KB/s, max write time: %i ms (=%7.2lf KB/s), fsync: %i ms", run,
  206  			 (double)block_size * num_blocks / elapsed / 1024.,

/Users/lorenzmeier/src/Firmware/src/systemcmds/tests/hrt_test/hrt_test.cpp:
   72  	hrt_abstime t = hrt_absolute_time();
   73  	px4_usleep(1000000);
   74: 	hrt_abstime elt = hrt_elapsed_time(&t);
   75  	PX4_INFO("Elapsed time %llu in 1 sec (usleep)\n", (unsigned long long)elt);
   76  	PX4_INFO("Start time %llu\n", (unsigned long long)t);
   ..
   78  	t = hrt_absolute_time();
   79  	px4_sleep(1);
   80: 	elt = hrt_elapsed_time(&t);
   81  	PX4_INFO("Elapsed time %llu in 1 sec (sleep)\n", (unsigned long long)elt);
   82  	PX4_INFO("Start time %llu\n", (unsigned long long)t);

/Users/lorenzmeier/src/Firmware/src/systemcmds/tests/test_microbench_hrt.cpp:
  138  {
  139  	PERF("hrt_absolute_time()", u_64_out = hrt_absolute_time(), 1000);
  140: 	PERF("hrt_elapsed_time()", u_64_out = hrt_elapsed_time(&u_64), 1000);
  141  
  142  	return true;

/Users/lorenzmeier/src/Firmware/src/systemcmds/tests/test_mixer.cpp:
  425  	unsigned sleepcount = 0;
  426  
  427: 	while (hrt_elapsed_time(&starttime) < INIT_TIME_US + RAMP_TIME_US + 2 * sleep_quantum_us) {
  428  
  429  		/* mix */
  ...
  439  
  440  			/* check mixed outputs to be zero during init phase */
  441: 			if (hrt_elapsed_time(&starttime) < INIT_TIME_US &&
  442  			    r_page_servos[i] != r_page_servo_disarmed[i]) {
  443  				PX4_ERR("disarmed servo value mismatch: %d vs %d", r_page_servos[i], r_page_servo_disarmed[i]);
  ...
  445  			}
  446  
  447: 			if (hrt_elapsed_time(&starttime) >= INIT_TIME_US &&
  448  			    r_page_servos[i] + 1 <= r_page_servo_disarmed[i]) {
  449  				PX4_ERR("ramp servo value mismatch");
  ...
  497  	should_arm = false;
  498  
  499: 	while (hrt_elapsed_time(&starttime) < 600000) {
  500  
  501  		/* mix */
  ...
  534  	should_arm = true;
  535  
  536: 	while (hrt_elapsed_time(&starttime) < 600000 + RAMP_TIME_US) {
  537  
  538  		/* mix */
  ...
  551  			//fprintf(stderr, "ramp:\t %d: out: %8.4f, servo: %d \n", i, (double)outputs[i], (int)r_page_servos[i]);
  552  
  553: 			if (hrt_elapsed_time(&starttime) < RAMP_TIME_US &&
  554  			    (r_page_servos[i] + 1 <= r_page_servo_disarmed[i] ||
  555  			     r_page_servos[i] > servo_predicted[i])) {
  ...
  559  
  560  			/* check post ramp phase */
  561: 			if (hrt_elapsed_time(&starttime) > RAMP_TIME_US &&
  562  			    abs(servo_predicted[i] - r_page_servos[i]) > 2) {
  563  				printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]);

/Users/lorenzmeier/src/Firmware/src/systemcmds/topic_listener/listener_main.cpp:
   86  
   87  		} else {
   88: 			if (hrt_elapsed_time(&start_time) > 2 * 1000 * 1000) {
   89  				PX4_INFO_RAW("Waited for 2 seconds without a message. Giving up.\n");
   90  				break;

147 matches across 65 files

@LorenzMeier LorenzMeier changed the title [WIP] HRT: Create new separate call for atomic HRT elapsed time calculation HRT: Create new separate call for atomic HRT elapsed time calculation Jan 20, 2019
@LorenzMeier LorenzMeier requested review from bkueng and dagar January 20, 2019 15:21
The actual implementation is not atomic, as the value on the application layer would be limited.
This reduces interrupt load significantly.
This reduces interrupt load significantly.
dagar
dagar previously approved these changes Jan 20, 2019
@LorenzMeier LorenzMeier requested a review from a team January 20, 2019 19:11
@LorenzMeier
Copy link
Member Author

@PX4/testflights Please clock up a couple hours on this. Thanks!

Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is one of the canges I've been meaning to do as well, thanks for looking into it.

I see a problematic call on the IO:

  • fmu_data_received_time is read in mixer.cpp, but it's written from an IRQ context in registers_set (registers.c).

src/systemcmds/sd_bench/sd_bench.c Outdated Show resolved Hide resolved
src/drivers/drv_hrt.h Outdated Show resolved Hide resolved
@Avysuarez
Copy link

Tested on pixhawk 4 and pixhawk 2.1
Good flights, no issues.
Pixhawk 2.1
https://review.px4.io/plot_app?log=4e06d7bc-b824-4cb5-af6a-a0a064cf864b
Pixhawk 4
https://review.px4.io/plot_app?log=63c668c6-2da5-49bf-947d-5ddc7f39af32

This leads to less jitter in the benchmark
@LorenzMeier
Copy link
Member Author

@bkueng I changed to the atomic call on IO.

This allows the compiler to optimize better without loosing any performance / accuracy.
This is required as we might be in interrupt context on this bare-metal target.
@LorenzMeier LorenzMeier force-pushed the pr-fix-hrt-elapsed-usage branch from 6193c13 to 17ea90b Compare January 22, 2019 21:41
@LorenzMeier LorenzMeier merged commit 3a7deef into master Jan 22, 2019
@LorenzMeier LorenzMeier deleted the pr-fix-hrt-elapsed-usage branch January 22, 2019 22:53
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Replace the atomic hrt_elapsed_time call with a non-atomic call
5 participants