mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
GCS_MAVLink: tidy handling of barometer calibrations
This commit is contained in:
parent
65893cfca5
commit
c6d7f5151a
@ -303,6 +303,7 @@ protected:
|
||||
virtual MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet);
|
||||
|
||||
virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet);
|
||||
virtual MAV_RESULT _handle_command_preflight_calibration_baro();
|
||||
|
||||
MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet);
|
||||
|
@ -2229,6 +2229,16 @@ bool GCS_MAVLINK::calibrate_gyros()
|
||||
return true;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro()
|
||||
{
|
||||
// fast barometer calibration
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Updating barometer calibration");
|
||||
AP::baro().update_calibration();
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
|
||||
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||
{
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
@ -2238,6 +2248,10 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
if (is_equal(packet.param3,1.0f)) {
|
||||
return _handle_command_preflight_calibration_baro();
|
||||
}
|
||||
|
||||
if (is_equal(packet.param5,1.0f)) {
|
||||
// start with gyro calibration
|
||||
if (!calibrate_gyros()) {
|
||||
|
Loading…
Reference in New Issue
Block a user