Browse Source

Copter:tradheli-spool logic fix for acro and stabilize

master
bnsgeyer 6 years ago committed by Randy Mackay
parent
commit
7ff3a49a10
  1. 2
      ArduCopter/mode_acro_heli.cpp
  2. 3
      ArduCopter/mode_stabilize_heli.cpp

2
ArduCopter/mode_acro_heli.cpp

@ -59,8 +59,6 @@ void Copter::ModeAcro_Heli::run() @@ -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);

3
ArduCopter/mode_stabilize_heli.cpp

@ -22,9 +22,6 @@ void Copter::ModeStabilize_Heli::run() @@ -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…
Cancel
Save