mirror of https://github.com/ArduPilot/ardupilot
AP_Tuning: eliminate GCS_MAVLINK::send_statustext_all
This commit is contained in:
parent
85756b7226
commit
33a974d7f5
|
@ -79,7 +79,7 @@ void AP_Tuning::check_selector_switch(void)
|
|||
// save tune
|
||||
save_parameters();
|
||||
re_center();
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Tuning: Saved");
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: Saved");
|
||||
AP_Notify::events.tune_save = 1;
|
||||
changed = false;
|
||||
need_revert = 0;
|
||||
|
@ -91,7 +91,7 @@ void AP_Tuning::check_selector_switch(void)
|
|||
if (hold_time < 2000) {
|
||||
// re-center the value
|
||||
re_center();
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm));
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm));
|
||||
} else if (hold_time < 5000) {
|
||||
// change parameter
|
||||
next_parameter();
|
||||
|
@ -126,7 +126,7 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
|||
// check for revert on changed flightmode
|
||||
if (flightmode != last_flightmode) {
|
||||
if (need_revert != 0 && mode_revert != 0) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Tuning: reverted");
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: reverted");
|
||||
revert_parameters();
|
||||
re_center();
|
||||
}
|
||||
|
@ -202,7 +202,7 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
|||
}
|
||||
// starting tuning
|
||||
mid_point_wait = false;
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Tuning: mid-point %s", get_tuning_name(current_parm));
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: mid-point %s", get_tuning_name(current_parm));
|
||||
AP_Notify::events.tune_started = 1;
|
||||
}
|
||||
last_channel_value = chan_value;
|
||||
|
@ -301,7 +301,7 @@ void AP_Tuning::next_parameter(void)
|
|||
}
|
||||
current_parm = tuning_sets[i].parms[current_parm_index];
|
||||
re_center();
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Tuning: started %s", get_tuning_name(current_parm));
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: started %s", get_tuning_name(current_parm));
|
||||
AP_Notify::events.tune_next = current_parm_index+1;
|
||||
break;
|
||||
}
|
||||
|
@ -331,7 +331,7 @@ void AP_Tuning::check_controller_error(void)
|
|||
uint32_t now = AP_HAL::millis();
|
||||
if (now - last_controller_error_ms > 2000 && hal.util->get_soft_armed()) {
|
||||
AP_Notify::events.tune_error = 1;
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Tuning: error %.2f", (double)err);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: error %.2f", (double)err);
|
||||
last_controller_error_ms = now;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue