Browse Source

TradHeli: use landing collective when landed or landing

master
Randy Mackay 11 years ago
parent
commit
3ce16113b5
  1. 11
      ArduCopter/ArduCopter.pde
  2. 28
      ArduCopter/heli.pde

11
ArduCopter/ArduCopter.pde

@ -1084,6 +1084,11 @@ static void throttle_loop() @@ -1084,6 +1084,11 @@ static void throttle_loop()
// check auto_armed status
update_auto_armed();
#if FRAME_CONFIG == HELI_FRAME
// update trad heli swash plate movement
heli_update_landing_swash();
#endif
}
// update_mount - update camera mount position
@ -1909,6 +1914,8 @@ void update_throttle_mode(void) @@ -1909,6 +1914,8 @@ void update_throttle_mode(void)
update_throttle_cruise(motors.get_collective_out());
#else
update_throttle_cruise(pilot_throttle_scaled);
#endif //HELI_FRAME
// check if we've taken off yet
if (!ap.takeoff_complete && motors.armed()) {
if (pilot_throttle_scaled > g.throttle_cruise) {
@ -1916,7 +1923,6 @@ void update_throttle_mode(void) @@ -1916,7 +1923,6 @@ void update_throttle_mode(void)
set_takeoff_complete(true);
}
}
#endif //HELI_FRAME
}
set_target_alt_for_reporting(0);
break;
@ -1934,13 +1940,14 @@ void update_throttle_mode(void) @@ -1934,13 +1940,14 @@ void update_throttle_mode(void)
update_throttle_cruise(motors.get_collective_out());
#else
update_throttle_cruise(pilot_throttle_scaled);
#endif //HELI_FRAME
if (!ap.takeoff_complete && motors.armed()) {
if (pilot_throttle_scaled > g.throttle_cruise) {
// we must be in the air by now
set_takeoff_complete(true);
}
}
#endif //HELI_FRAME
}
set_target_alt_for_reporting(0);
break;

28
ArduCopter/heli.pde

@ -204,4 +204,30 @@ get_heli_rate_yaw(int32_t target_rate) @@ -204,4 +204,30 @@ get_heli_rate_yaw(int32_t target_rate)
return output; // output control
}
#endif // FRAME_CONFIG == TRAD_HELI
// heli_update_landing_swash - sets swash plate flag so higher minimum is used when landed or landing
// should be called soon after update_land_detector in main code
static void heli_update_landing_swash()
{
switch(throttle_mode) {
case THROTTLE_MANUAL:
case THROTTLE_MANUAL_TILT_COMPENSATED:
case THROTTLE_MANUAL_HELI:
// manual modes always uses full swash range
motors.set_collective_for_landing(false);
break;
case THROTTLE_LAND:
// landing always uses limit swash range
motors.set_collective_for_landing(true);
break;
case THROTTLE_HOLD:
case THROTTLE_AUTO:
default:
// auto and hold use limited swash when landed
motors.set_collective_for_landing(ap.land_complete || !ap.auto_armed);
break;
}
}
#endif // FRAME_CONFIG == HELI_FRAME
Loading…
Cancel
Save