mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
commander: calibration restore sleep after CAL_QGC_DONE_MSG/CAL_QGC_FAILED_MSG
This commit is contained in:
@@ -442,11 +442,13 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
|
|||||||
|
|
||||||
if (!failed) {
|
if (!failed) {
|
||||||
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name);
|
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;
|
return PX4_OK;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name);
|
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;
|
return PX4_ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -338,10 +338,13 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
|
|||||||
|
|
||||||
if (!failed) {
|
if (!failed) {
|
||||||
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name);
|
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;
|
return PX4_OK;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name);
|
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;
|
return PX4_ERROR;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -175,10 +175,12 @@ out:
|
|||||||
|
|
||||||
if (success) {
|
if (success) {
|
||||||
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, "level");
|
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, "level");
|
||||||
|
px4_usleep(600000); // give this message enough time to propagate
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "level");
|
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "level");
|
||||||
|
px4_usleep(600000); // give this message enough time to propagate
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user