mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter:tradheli-spool logic fix for acro and stabilize
This commit is contained in:
parent
593925567b
commit
7ff3a49a10
@ -59,8 +59,6 @@ void Copter::ModeAcro_Heli::run()
|
||||
}
|
||||
}
|
||||
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
if (!motors->has_flybar()){
|
||||
// convert the input to the desired body frame rate
|
||||
get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw);
|
||||
|
@ -22,9 +22,6 @@ void Copter::ModeStabilize_Heli::run()
|
||||
float target_yaw_rate;
|
||||
float pilot_throttle_scaled;
|
||||
|
||||
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user