Skip to content

Commit

Permalink
AP_WheelEncoder: correct compilation when HAL_GCS_ENABLED is false
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Mar 7, 2024
1 parent 3ff7901 commit 2398222
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand All @@ -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;
}

Expand All @@ -86,4 +86,4 @@ void AP_WheelEncoder_SITL_Quadrature::update(void)
copy_state_to_frontend(_distance_count, _total_count, 0, time_now);
}

#endif
#endif

0 comments on commit 2398222

Please sign in to comment.