mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: correct compilation when GCS library not available
This commit is contained in:
parent
1bf85a0a15
commit
673fad04de
|
@ -59,7 +59,7 @@ void AP_WindVane_Analog::calibrate()
|
|||
_cal_start_ms = AP_HAL::millis();
|
||||
_cal_volt_max = _current_analog_voltage;
|
||||
_cal_volt_min = _current_analog_voltage;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "WindVane: Calibration started, rotate wind vane");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: Calibration started, rotate wind vane");
|
||||
}
|
||||
|
||||
// record min and max voltage
|
||||
|
@ -74,11 +74,11 @@ void AP_WindVane_Analog::calibrate()
|
|||
// save min and max voltage
|
||||
_frontend._dir_analog_volt_max.set_and_save(_cal_volt_max);
|
||||
_frontend._dir_analog_volt_min.set_and_save(_cal_volt_min);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "WindVane: Calibration complete (volt min:%.1f max:%1.f)",
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: Calibration complete (volt min:%.1f max:%1.f)",
|
||||
(double)_cal_volt_min,
|
||||
(double)_cal_volt_max);
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "WindVane: Calibration failed (volt diff %.1f below %.1f)",
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: Calibration failed (volt diff %.1f below %.1f)",
|
||||
(double)volt_diff,
|
||||
(double)WINDVANE_CALIBRATION_VOLT_DIFF_MIN);
|
||||
}
|
||||
|
|
|
@ -31,7 +31,7 @@ AP_WindVane_Backend::AP_WindVane_Backend(AP_WindVane &frontend) :
|
|||
// calibrate WindVane
|
||||
void AP_WindVane_Backend::calibrate()
|
||||
{
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "WindVane: No cal required");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: No cal required");
|
||||
_frontend._calibration.set_and_save(0);
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -70,7 +70,7 @@ void AP_WindVane_ModernDevice::update_speed()
|
|||
|
||||
void AP_WindVane_ModernDevice::calibrate()
|
||||
{
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "WindVane: rev P. zero wind voltage offset set to %.1f",double(_current_analog_voltage));
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: rev P. zero wind voltage offset set to %.1f",double(_current_analog_voltage));
|
||||
_frontend._speed_sensor_voltage_offset.set_and_save(_current_analog_voltage);
|
||||
_frontend._calibration.set_and_save(0);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue