Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AC_AutoTune: make safe shutdown for tradheli when landing in Autotune #27423

Merged
merged 2 commits into from
Jul 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,9 @@ class Mode {
virtual bool pause() { return false; };
virtual bool resume() { return false; };

// handle situations where the vehicle is on the ground waiting for takeoff
void make_safe_ground_handling(bool force_throttle_unlimited = false);
rmackay9 marked this conversation as resolved.
Show resolved Hide resolved

// true if weathervaning is allowed in the current mode
#if WEATHERVANE_ENABLED == ENABLED
virtual bool allows_weathervaning() const { return false; }
Expand All @@ -196,7 +199,6 @@ class Mode {
bool is_disarmed_or_landed() const;
void zero_throttle_and_relax_ac(bool spool_up = false);
void zero_throttle_and_hold_attitude();
void make_safe_ground_handling(bool force_throttle_unlimited = false);

// Return stopping point as a location with above origin alt frame
Location get_stopping_point() const;
Expand Down
34 changes: 12 additions & 22 deletions ArduCopter/mode_autotune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,30 +38,20 @@ void AutoTune::run()
// apply SIMPLE mode transform to pilot inputs
copter.update_simple_mode();

// reset target lean angles and heading while landed
// disarm when the landing detector says we've landed and spool state is ground idle
Copy link
Contributor

@rmackay9 rmackay9 Jun 30, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

disarming when the vehicle becomes landed is available as a flight option (or arming option?) but its not the default so I think this would surprise users

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Well, we would never allow the user to takeoff in autotune so why would we leave the aircraft in an armed state after landing. Plus disarming would then save the gains which i think is helpful for the user.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we don't allow users to arm in autotune but they can takeoff in autotune. It's really more a matter of consistency though. If we want the vehicle to always disarm while landed we can discuss and perhaps make that change but having different modes behave differently is confusing to the user

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There isn’t any logic in autotune to support takeoff.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I tend to agree with @rmackay9 I want disarm to be under my control, not autotune - this would also be a surprise.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The alternative is to ignore any positive climb rate or switch out of mot_spin_arm after landed but still let the user disarm.

if (copter.ap.land_complete && motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) {
copter.arming.disarm(AP_Arming::Method::LANDED);
}

// if not armed set throttle to zero and exit immediately
if (copter.ap.land_complete) {
// we are landed, shut down
float target_climb_rate = get_pilot_desired_climb_rate_cms();

// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@rmackay9 I suppose this would allow users to takeoff. however this is far from the current code in althold and loiter used for spool state management and takeoff.

IMHO, I don't think it is a good/safe practice to allow takeoff in autotune. @lthall what do you think?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The first twitch of autotune can be very large and aggressive. If we let people take-off in autotune and they hover at 1m for a second that first twitch could easily cause a crash.

Given we switch to Autotune from Loiter or Alt_Hold to determine what behaviour we use I don't think we should be starting in Autotune.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In case it matters, I think this is an existing issue

} else {
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
}
copter.attitude_control->reset_rate_controller_I_terms_smoothly();
copter.attitude_control->reset_yaw_target_and_rate();

float target_roll, target_pitch, target_yaw_rate;
get_pilot_desired_rp_yrate_cd(target_roll, target_pitch, target_yaw_rate);

copter.attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
copter.pos_control->relax_z_controller(0.0f);
copter.pos_control->update_z_controller();
} else {
// run autotune mode
AC_AutoTune::run();
copter.flightmode->make_safe_ground_handling();
return;
}

// run autotune mode
AC_AutoTune::run();

}


Expand Down
Loading