mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_Autotune: add axis string function
This commit is contained in:
parent
58e2e84432
commit
894f924de0
@ -157,6 +157,20 @@ const char *AC_AutoTune::type_string() const
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||
}
|
||||
|
||||
// return current axis string
|
||||
const char *AC_AutoTune::axis_string() const
|
||||
{
|
||||
switch (axis) {
|
||||
case ROLL:
|
||||
return "Roll";
|
||||
case PITCH:
|
||||
return "Pitch";
|
||||
case YAW:
|
||||
return "Yaw";
|
||||
}
|
||||
return "";
|
||||
}
|
||||
|
||||
// run - runs the autotune flight mode
|
||||
// should be called at 100hz or more
|
||||
void AC_AutoTune::run()
|
||||
|
@ -171,6 +171,9 @@ protected:
|
||||
// convert tune type to string for reporting
|
||||
const char *type_string() const;
|
||||
|
||||
// return current axis string
|
||||
const char *axis_string() const;
|
||||
|
||||
// Functions added for heli autotune
|
||||
|
||||
// Add additional updating gain functions specific to heli
|
||||
|
@ -267,20 +267,8 @@ void AC_AutoTune_Heli::do_gcs_announcements()
|
||||
if (now - announce_time < AUTOTUNE_ANNOUNCE_INTERVAL_MS) {
|
||||
return;
|
||||
}
|
||||
char axis_char = '?';
|
||||
switch (axis) {
|
||||
case ROLL:
|
||||
axis_char = 'R';
|
||||
break;
|
||||
case PITCH:
|
||||
axis_char = 'P';
|
||||
break;
|
||||
case YAW:
|
||||
axis_char = 'Y';
|
||||
break;
|
||||
}
|
||||
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: (%c) %s", axis_char, type_string());
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: %s %s", axis_string(), type_string());
|
||||
send_step_string();
|
||||
switch (tune_type) {
|
||||
case RD_UP:
|
||||
|
Loading…
Reference in New Issue
Block a user