mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-07 09:13:32 +08:00
Gyro: also output to console
This commit is contained in:
@@ -122,7 +122,7 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void* data)
|
||||
}
|
||||
|
||||
if (s == 0 && calibration_counter[0] % (calibration_count / 20) == 0) {
|
||||
mavlink_log_info(worker_data->mavlink_fd, CAL_QGC_PROGRESS_MSG, (calibration_counter[0] * 100) / calibration_count);
|
||||
mavlink_and_console_log_info(worker_data->mavlink_fd, CAL_QGC_PROGRESS_MSG, (calibration_counter[0] * 100) / calibration_count);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -131,14 +131,14 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void* data)
|
||||
}
|
||||
|
||||
if (poll_errcount > 1000) {
|
||||
mavlink_log_critical(worker_data->mavlink_fd, CAL_ERROR_SENSOR_MSG);
|
||||
mavlink_and_console_log_critical(worker_data->mavlink_fd, CAL_ERROR_SENSOR_MSG);
|
||||
return calibrate_return_error;
|
||||
}
|
||||
}
|
||||
|
||||
for (unsigned s = 0; s < max_gyros; s++) {
|
||||
if (worker_data->device_id[s] != 0 && calibration_counter[s] < calibration_count / 2) {
|
||||
mavlink_log_critical(worker_data->mavlink_fd, "[cal] ERROR: missing data, sensor %d", s)
|
||||
mavlink_and_console_log_critical(worker_data->mavlink_fd, "[cal] ERROR: missing data, sensor %d", s)
|
||||
return calibrate_return_error;
|
||||
}
|
||||
|
||||
@@ -155,7 +155,7 @@ int do_gyro_calibration(int mavlink_fd)
|
||||
int res = OK;
|
||||
gyro_worker_data_t worker_data = {};
|
||||
|
||||
mavlink_log_info(mavlink_fd, CAL_QGC_STARTED_MSG, sensor_name);
|
||||
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_STARTED_MSG, sensor_name);
|
||||
|
||||
worker_data.mavlink_fd = mavlink_fd;
|
||||
|
||||
@@ -179,7 +179,7 @@ int do_gyro_calibration(int mavlink_fd)
|
||||
(void)sprintf(str, "CAL_GYRO%u_ID", s);
|
||||
res = param_set_no_notification(param_find(str), &(worker_data.device_id[s]));
|
||||
if (res != OK) {
|
||||
mavlink_log_critical(mavlink_fd, "[cal] Unable to reset CAL_GYRO%u_ID", s);
|
||||
mavlink_and_console_log_critical(mavlink_fd, "[cal] Unable to reset CAL_GYRO%u_ID", s);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
@@ -193,7 +193,7 @@ int do_gyro_calibration(int mavlink_fd)
|
||||
px4_close(fd);
|
||||
|
||||
if (res != OK) {
|
||||
mavlink_log_critical(mavlink_fd, CAL_ERROR_RESET_CAL_MSG, s);
|
||||
mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_RESET_CAL_MSG, s);
|
||||
return ERROR;
|
||||
}
|
||||
}
|
||||
@@ -302,7 +302,7 @@ int do_gyro_calibration(int mavlink_fd)
|
||||
px4_close(fd);
|
||||
|
||||
if (res != OK) {
|
||||
mavlink_log_critical(mavlink_fd, CAL_ERROR_APPLY_CAL_MSG);
|
||||
mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_APPLY_CAL_MSG);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -325,7 +325,7 @@ int do_gyro_calibration(int mavlink_fd)
|
||||
res = param_save_default();
|
||||
|
||||
if (res != OK) {
|
||||
mavlink_log_critical(mavlink_fd, CAL_ERROR_SAVE_PARAMS_MSG);
|
||||
mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_SAVE_PARAMS_MSG);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -333,9 +333,9 @@ int do_gyro_calibration(int mavlink_fd)
|
||||
usleep(200000);
|
||||
|
||||
if (res == OK) {
|
||||
mavlink_log_info(mavlink_fd, CAL_QGC_DONE_MSG, sensor_name);
|
||||
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_DONE_MSG, sensor_name);
|
||||
} else {
|
||||
mavlink_log_info(mavlink_fd, CAL_QGC_FAILED_MSG, sensor_name);
|
||||
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_FAILED_MSG, sensor_name);
|
||||
}
|
||||
|
||||
/* give this message enough time to propagate */
|
||||
|
||||
Reference in New Issue
Block a user