mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: update_thr_cruise removed from control_stabilize
This commit is contained in:
parent
223c6fd4de
commit
aedb4136de
@ -61,7 +61,4 @@ static void stabilize_run()
|
||||
control_roll = angle_target.x;
|
||||
control_pitch = angle_target.y;
|
||||
control_yaw = angle_target.z;
|
||||
|
||||
// update estimate of throttle cruise
|
||||
update_throttle_cruise(pilot_throttle_scaled);
|
||||
}
|
||||
|
@ -47,9 +47,6 @@ static void heli_stabilize_run()
|
||||
control_roll = angle_target.x;
|
||||
control_pitch = angle_target.y;
|
||||
control_yaw = angle_target.z;
|
||||
|
||||
// update estimate of throttle cruise
|
||||
update_throttle_cruise(motors.get_collective_out());
|
||||
}
|
||||
|
||||
#endif //HELI_FRAME
|
||||
|
Loading…
Reference in New Issue
Block a user