mirror of https://github.com/ArduPilot/ardupilot
Copter: integrate pre-takeoff throttle feedback
This feature slightly revs the motors in response to the pilot's input before takeoff AltHold, Loiter, AutoTune, PosHold and Sport flight modes pair-programmed with Randy Mackay
This commit is contained in:
parent
11678ba936
commit
9202149fb1
|
@ -59,8 +59,8 @@ static void althold_run()
|
|||
if (ap.land_complete) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
// move throttle to minimum to keep us on the ground
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
|
||||
}else{
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
|
|
@ -243,8 +243,8 @@ static void autotune_run()
|
|||
if (ap.land_complete) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
// move throttle to minimum to keep us on the ground
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
|
||||
}else{
|
||||
// check if pilot is overriding the controls
|
||||
if (target_roll != 0 || target_pitch != 0 || target_yaw_rate != 0.0f || target_climb_rate != 0) {
|
||||
|
|
|
@ -72,7 +72,8 @@ static void loiter_run()
|
|||
wp_nav.init_loiter_target();
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
|
||||
}else{
|
||||
// run loiter controller
|
||||
wp_nav.update_loiter();
|
||||
|
|
|
@ -70,7 +70,8 @@ static void ofloiter_run()
|
|||
if (ap.land_complete) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
|
||||
reset_optflow_I();
|
||||
}else{
|
||||
// mix in user control with optical flow
|
||||
|
|
|
@ -188,7 +188,8 @@ static void poshold_run()
|
|||
wp_nav.init_loiter_target();
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
|
||||
return;
|
||||
}else{
|
||||
// convert pilot input to lean angles
|
||||
|
|
|
@ -78,8 +78,8 @@ static void sport_run()
|
|||
if (ap.land_complete) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
// move throttle to minimum to keep us on the ground
|
||||
attitude_control.set_throttle_out(0, false);
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
|
||||
}else{
|
||||
|
||||
// call attitude controller
|
||||
|
|
Loading…
Reference in New Issue