diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp index 4b7b62a7d9..a23397881e 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp @@ -69,6 +69,7 @@ bool AP_OpticalFlow_Calibrator::update() { // prefix for reporting const char* prefix_str = "FlowCal:"; + (void)prefix_str; // in case !HAL_GCS_ENABLED // while running add samples if (_cal_state == CalState::RUNNING) { @@ -190,7 +191,9 @@ bool AP_OpticalFlow_Calibrator::calc_scalars(uint8_t axis, float& scalar, float& { // prefix for reporting const char* prefix_str = "FlowCal:"; + (void)prefix_str; // in case !HAL_GCS_ENABLED const char* axis_str = axis == 0 ? "x" : "y"; + (void)axis_str; // in case !HAL_GCS_ENABLED // check we have samples // this should never fail because this method should only be called once the sample buffer is full