From 23982229fb0a586fc455bed776d374e5f6ca7621 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 7 Mar 2024 18:52:59 +1100 Subject: [PATCH] AP_WheelEncoder: correct compilation when HAL_GCS_ENABLED is false --- libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp b/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp index 5caa9f0d19..9fc073d545 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp +++ b/libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp @@ -55,7 +55,7 @@ void AP_WheelEncoder_SITL_Quadrature::update(void) // distance from center of wheel axis to each wheel const double half_wheelbase = ( fabsf(_frontend.get_pos_offset(0).y) + fabsf(_frontend.get_pos_offset(1).y) )/2.0f; if (is_zero(half_wheelbase)) { - gcs().send_text(MAV_SEVERITY_WARNING, "WheelEncoder: wheel offset not set!"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "WheelEncoder: wheel offset not set!"); } if (_state.instance == 0) { @@ -69,7 +69,7 @@ void AP_WheelEncoder_SITL_Quadrature::update(void) const double radius = _frontend.get_wheel_radius(_state.instance); if (is_zero(radius)) { // avoid divide by zero - gcs().send_text(MAV_SEVERITY_WARNING, "WheelEncoder: wheel radius not set!"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "WheelEncoder: wheel radius not set!"); return; } @@ -86,4 +86,4 @@ void AP_WheelEncoder_SITL_Quadrature::update(void) copy_state_to_frontend(_distance_count, _total_count, 0, time_now); } -#endif \ No newline at end of file +#endif