From d478a40edcffd6910244e5baf5a6957e3032a61e Mon Sep 17 00:00:00 2001 From: murata Date: Mon, 21 Mar 2022 18:26:30 +0900 Subject: [PATCH] AP_Mount: Console output can be disabled --- libraries/AP_Mount/SoloGimbalEKF.cpp | 4 ++-- libraries/AP_Mount/SoloGimbal_Parameters.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Mount/SoloGimbalEKF.cpp b/libraries/AP_Mount/SoloGimbalEKF.cpp index 37d0c1dada..0003d34360 100644 --- a/libraries/AP_Mount/SoloGimbalEKF.cpp +++ b/libraries/AP_Mount/SoloGimbalEKF.cpp @@ -107,7 +107,7 @@ void SoloGimbalEKF::RunEKF(float delta_time, const Vector3f &delta_angles, const for (uint8_t i=3; i <= 5; i++) Cov[i][i] = sq(Sigma_velNED); for (uint8_t i=6; i <= 8; i++) Cov[i][i] = sq(Sigma_dAngBias); FiltInit = true; - hal.console->printf("\nSoloGimbalEKF Alignment Started\n"); + DEV_PRINTF("\nSoloGimbalEKF Alignment Started\n"); // Don't run the filter in this timestep because we have already used the delta velocity data to set an initial orientation return; @@ -142,7 +142,7 @@ void SoloGimbalEKF::RunEKF(float delta_time, const Vector3f &delta_angles, const //calculate the initial heading using magnetometer, estimated tilt and declination alignHeading(); YawAligned = true; - hal.console->printf("\nSoloGimbalEKF Alignment Completed\n"); + DEV_PRINTF("\nSoloGimbalEKF Alignment Completed\n"); } // Fuse magnetometer data if we have new measurements and an aligned heading diff --git a/libraries/AP_Mount/SoloGimbal_Parameters.cpp b/libraries/AP_Mount/SoloGimbal_Parameters.cpp index 4864a59acd..8245086ba3 100644 --- a/libraries/AP_Mount/SoloGimbal_Parameters.cpp +++ b/libraries/AP_Mount/SoloGimbal_Parameters.cpp @@ -162,7 +162,7 @@ void SoloGimbal_Parameters::update() for(uint8_t i=0; i _max_fetch_attempts) { _params[i].state = GMB_PARAMSTATE_NONEXISTANT; - hal.console->printf("Gimbal parameter %s timed out\n", get_param_name((gmb_param_t)i)); + DEV_PRINTF("Gimbal parameter %s timed out\n", get_param_name((gmb_param_t)i)); } }