mirror of https://github.com/ArduPilot/ardupilot
AP_WheelEncoder: correct compilation when HAL_GCS_ENABLED is false
This commit is contained in:
parent
3ff790159f
commit
23982229fb
|
@ -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
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue