mirror of https://github.com/ArduPilot/ardupilot
Copter: Tradheli manage yaw better on the ground.
This commit is contained in:
parent
9fcbc77ce0
commit
534ba89756
|
@ -44,7 +44,22 @@ void Copter::althold_run()
|
|||
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters are held on the ground until rotor speed runup has finished
|
||||
bool takeoff_triggered = (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()) && motors.rotor_runup_complete());
|
||||
|
||||
if(!motors.armed()) {
|
||||
heli_flags.init_targets_on_arming=true;
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
}
|
||||
|
||||
// if we have recently armed and rotor is just ramping up speed, relax yaw controller
|
||||
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
if (motors.rotor_speed_above_critical()) {
|
||||
heli_flags.init_targets_on_arming=false;
|
||||
}
|
||||
}
|
||||
#else
|
||||
bool takeoff_triggered = (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()));
|
||||
#endif
|
||||
|
|
|
@ -33,10 +33,13 @@ void Copter::heli_acro_run()
|
|||
heli_flags.init_targets_on_arming=true;
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
}
|
||||
|
||||
|
||||
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
||||
heli_flags.init_targets_on_arming=false;
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
if (motors.rotor_speed_above_critical()) {
|
||||
heli_flags.init_targets_on_arming=false;
|
||||
}
|
||||
}
|
||||
|
||||
// send RC inputs direct into motors library for use during manual passthrough for helicopter setup
|
||||
|
|
|
@ -36,8 +36,11 @@ void Copter::heli_stabilize_run()
|
|||
}
|
||||
|
||||
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
||||
heli_flags.init_targets_on_arming=false;
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
if (motors.rotor_speed_above_critical()) {
|
||||
heli_flags.init_targets_on_arming=false;
|
||||
}
|
||||
}
|
||||
|
||||
// send RC inputs direct into motors library for use during manual passthrough for helicopter setup
|
||||
|
|
Loading…
Reference in New Issue