mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: flip uses 0 to 1 throttle and sets motor spool state
This commit is contained in:
parent
8a49745e96
commit
068fc7feac
@ -96,7 +96,7 @@ bool Copter::flip_init(bool ignore_checks)
|
||||
// should be called at 100hz or more
|
||||
void Copter::flip_run()
|
||||
{
|
||||
int16_t throttle_out;
|
||||
float throttle_out;
|
||||
float recovery_angle;
|
||||
|
||||
// if pilot inputs roll > 40deg or timeout occurs abandon flip
|
||||
@ -219,8 +219,11 @@ void Copter::flip_run()
|
||||
break;
|
||||
}
|
||||
|
||||
// set motors to full range
|
||||
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
// output pilot's throttle without angle boost
|
||||
if (throttle_out == 0) {
|
||||
if (is_zero(throttle_out)) {
|
||||
attitude_control.set_throttle_out_unstabilized(0,false,g.throttle_filt);
|
||||
} else {
|
||||
attitude_control.set_throttle_out(throttle_out, false, g.throttle_filt);
|
||||
|
Loading…
Reference in New Issue
Block a user