mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
AP_Mount: Console output can be disabled
This commit is contained in:
parent
6102e094be
commit
d478a40edc
libraries/AP_Mount
@ -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
|
||||
|
@ -162,7 +162,7 @@ void SoloGimbal_Parameters::update()
|
||||
for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
|
||||
if (!_params[i].seen && _params[i].fetch_attempts > _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));
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user