mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
rc_check: cleanup mavlink log messages
This commit is contained in:
parent
c47cd972a8
commit
30bc248138
@ -73,7 +73,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
param_t trans_parm = param_find("RC_MAP_TRANS_SW");
|
||||
|
||||
if (trans_parm == PARAM_INVALID) {
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "ERR: RC_MAP_TRANS_SW PARAMETER MISSING"); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC_MAP_TRANS_SW PARAMETER MISSING."); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
@ -84,7 +84,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
param_get(trans_parm, &transition_switch);
|
||||
|
||||
if (transition_switch < 1) {
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "ERR: transition switch (RC_MAP_TRANS_SW) not set"); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "Transition switch RC_MAP_TRANS_SW not set."); }
|
||||
|
||||
map_fail_count++;
|
||||
}
|
||||
@ -98,7 +98,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
param_t map_parm = param_find(rc_map_mandatory[j]);
|
||||
|
||||
if (map_parm == PARAM_INVALID) {
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERR: PARAM %s MISSING", rc_map_mandatory[j]); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: PARAM %s MISSING.", rc_map_mandatory[j]); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
@ -111,7 +111,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
param_get(map_parm, &mapping);
|
||||
|
||||
if (mapping > RC_INPUT_MAX_CHANNELS) {
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERR: %s >= # CHANS", rc_map_mandatory[j]); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: %s >= NUMBER OF CHANNELS.", rc_map_mandatory[j]); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
@ -119,7 +119,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
}
|
||||
|
||||
if (mapping == 0) {
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERR: Mandatory %s is unmapped", rc_map_mandatory[j]); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: mandatory %s is unmapped.", rc_map_mandatory[j]); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
@ -172,7 +172,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
if (param_min < RC_INPUT_LOWEST_MIN_US) {
|
||||
count++;
|
||||
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERR: RC_%d_MIN < %u", i + 1, RC_INPUT_LOWEST_MIN_US); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC_%d_MIN < %u.", i + 1, RC_INPUT_LOWEST_MIN_US); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
@ -181,7 +181,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
if (param_max > RC_INPUT_HIGHEST_MAX_US) {
|
||||
count++;
|
||||
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERR: RC_%d_MAX > %u", i + 1, RC_INPUT_HIGHEST_MAX_US); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC_%d_MAX > %u.", i + 1, RC_INPUT_HIGHEST_MAX_US); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
@ -190,7 +190,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
if (param_trim < param_min) {
|
||||
count++;
|
||||
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERR: RC_%d_TRIM < MIN (%d/%d)", i + 1, (int)param_trim, (int)param_min); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC_%d_TRIM < MIN (%d/%d).", i + 1, (int)param_trim, (int)param_min); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
@ -199,7 +199,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
if (param_trim > param_max) {
|
||||
count++;
|
||||
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERR: RC_%d_TRIM > MAX (%d/%d)", i + 1, (int)param_trim, (int)param_max); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC_%d_TRIM > MAX (%d/%d).", i + 1, (int)param_trim, (int)param_max); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
@ -207,7 +207,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
|
||||
|
||||
/* assert deadzone is sane */
|
||||
if (param_dz > RC_INPUT_MAX_DEADZONE_US) {
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERR: RC_%d_DZ > %u", i + 1, RC_INPUT_MAX_DEADZONE_US); }
|
||||
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC_%d_DZ > %u.", i + 1, RC_INPUT_MAX_DEADZONE_US); }
|
||||
|
||||
/* give system time to flush error message in case there are more */
|
||||
usleep(100000);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user