Browse Source

airspeed calibration: instruct to blow into front of pitot

... rather than across it
release/1.12
Hamish Willee 4 years ago committed by Daniel Agar
parent
commit
d3fd03a014
  1. 2
      src/modules/commander/airspeed_calibration.cpp

2
src/modules/commander/airspeed_calibration.cpp

@ -199,7 +199,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub) @@ -199,7 +199,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub)
/* wait 500 ms to ensure parameter propagated through the system */
px4_usleep(500 * 1000);
calibration_log_critical(mavlink_log_pub, "[cal] Blow across front of pitot without touching");
calibration_log_critical(mavlink_log_pub, "[cal] Blow into front of pitot without touching");
calibration_counter = 0;

Loading…
Cancel
Save