commander: calibration restore sleep after CAL_QGC_DONE_MSG/CAL_QGC_FAILED_MSG

This commit is contained in:
Daniel Agar 2020-10-19 22:16:55 -04:00
parent 171bd6d784
commit 69986affbf
3 changed files with 7 additions and 0 deletions

View File

@ -442,11 +442,13 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
if (!failed) {
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name);
px4_usleep(600000); // give this message enough time to propagate
return PX4_OK;
}
}
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name);
px4_usleep(600000); // give this message enough time to propagate
return PX4_ERROR;
}

View File

@ -338,10 +338,13 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
if (!failed) {
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name);
px4_usleep(600000); // give this message enough time to propagate
return PX4_OK;
}
}
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name);
px4_usleep(600000); // give this message enough time to propagate
return PX4_ERROR;
}

View File

@ -175,10 +175,12 @@ out:
if (success) {
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, "level");
px4_usleep(600000); // give this message enough time to propagate
return 0;
} else {
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "level");
px4_usleep(600000); // give this message enough time to propagate
return 1;
}
}