Browse Source

TradHeli: remove calls to get_manual_collective in auto throttle

set_collective_for_landing method makes this unnecessary
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
81fc24586e
  1. 5
      ArduCopter/ArduCopter.pde
  2. 10
      ArduCopter/Attitude.pde

5
ArduCopter/ArduCopter.pde

@ -2004,13 +2004,8 @@ void update_throttle_mode(void) @@ -2004,13 +2004,8 @@ void update_throttle_mode(void)
get_throttle_althold_with_slew(wp_nav.get_desired_alt(), -wp_nav.get_descent_velocity(), wp_nav.get_climb_velocity());
set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint
}else{
#if FRAME_CONFIG == HELI_FRAME
// collective pitch should not be full negative to avoid harshing the mechanics. Use Stab Coll Min.
set_throttle_out(motors.get_manual_collective_min(), false);
#else
// pilot's throttle must be at zero so keep motors off
set_throttle_out(0, false);
#endif // HELI_FRAME
// deactivate accel based throttle controller
throttle_accel_deactivate();
set_target_alt_for_reporting(0);

10
ArduCopter/Attitude.pde

@ -917,17 +917,7 @@ get_throttle_accel(int16_t z_target_accel) @@ -917,17 +917,7 @@ get_throttle_accel(int16_t z_target_accel)
d = g.pid_throttle_accel.get_d(z_accel_error, .01f);
#if FRAME_CONFIG == HELI_FRAME
if (ap.takeoff_complete == true){
output = constrain_float(p+i+d+g.throttle_cruise, g.throttle_min, g.throttle_max);
} else {
// Avoid harshing the mechanics pushing into the ground
// stab_col_min should gently push down on the ground
output = constrain_float(p+i+d+g.throttle_cruise, motors.get_manual_collective_min(), motors.get_manual_collective_max());
}
#else
output = constrain_float(p+i+d+g.throttle_cruise, g.throttle_min, g.throttle_max);
#endif // HELI_FRAME
#if LOGGING_ENABLED == ENABLED
// log output if PID loggins is on and we are tuning the yaw

Loading…
Cancel
Save