|
|
|
@ -107,7 +107,6 @@ void ModePosHold::run()
@@ -107,7 +107,6 @@ void ModePosHold::run()
|
|
|
|
|
switch (poshold_state) { |
|
|
|
|
|
|
|
|
|
case AltHold_MotorStopped: |
|
|
|
|
|
|
|
|
|
attitude_control->reset_rate_controller_I_terms(); |
|
|
|
|
attitude_control->set_yaw_target_to_current_heading(); |
|
|
|
|
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
|
|
|
|
@ -121,7 +120,6 @@ void ModePosHold::run()
@@ -121,7 +120,6 @@ void ModePosHold::run()
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AltHold_Takeoff: |
|
|
|
|
|
|
|
|
|
// initiate take-off
|
|
|
|
|
if (!takeoff.running()) { |
|
|
|
|
takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); |
|
|
|
@ -148,16 +146,14 @@ void ModePosHold::run()
@@ -148,16 +146,14 @@ void ModePosHold::run()
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AltHold_Landed_Ground_Idle: |
|
|
|
|
|
|
|
|
|
loiter_nav->clear_pilot_desired_acceleration(); |
|
|
|
|
loiter_nav->init_target(); |
|
|
|
|
loiter_nav->update(); |
|
|
|
|
attitude_control->reset_rate_controller_I_terms(); |
|
|
|
|
attitude_control->set_yaw_target_to_current_heading(); |
|
|
|
|
// FALLTHROUGH
|
|
|
|
|
|
|
|
|
|
case AltHold_Landed_Pre_Takeoff: |
|
|
|
|
|
|
|
|
|
attitude_control->reset_rate_controller_I_terms(); |
|
|
|
|
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
|
|
|
|
|
|
|
|
|
|
// set poshold state to pilot override
|
|
|
|
@ -166,7 +162,6 @@ void ModePosHold::run()
@@ -166,7 +162,6 @@ void ModePosHold::run()
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AltHold_Flying: |
|
|
|
|
|
|
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); |
|
|
|
|
|
|
|
|
|
#if AC_AVOID_ENABLED == ENABLED |
|
|
|
|