Skip to content

Commit

Permalink
AC_AutoTune: make safe spool down for tradheli
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed Jul 2, 2024
1 parent 5fa2fcf commit 6f69a6b
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 23 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,7 @@ class Mode {
// pause and resume a mode
virtual bool pause() { return false; };
virtual bool resume() { return false; };
void make_safe_ground_handling(bool force_throttle_unlimited = false);

// true if weathervaning is allowed in the current mode
#if WEATHERVANE_ENABLED == ENABLED
Expand All @@ -196,7 +197,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
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);
} 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

0 comments on commit 6f69a6b

Please sign in to comment.