Browse Source

Copter: reset target alt to current alt when landed

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
52a3dc2bde
  1. 3
      ArduCopter/control_althold.pde
  2. 2
      ArduCopter/control_autotune.pde
  3. 1
      ArduCopter/control_circle.pde
  4. 2
      ArduCopter/control_loiter.pde
  5. 2
      ArduCopter/control_ofloiter.pde
  6. 3
      ArduCopter/control_poshold.pde
  7. 2
      ArduCopter/control_sport.pde

3
ArduCopter/control_althold.pde

@ -27,10 +27,10 @@ static void althold_run()
// if not auto armed set throttle to zero and exit immediately // if not auto armed set throttle to zero and exit immediately
if(!ap.auto_armed) { if(!ap.auto_armed) {
// To-Do: reset altitude target if we're somehow not landed?
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -61,6 +61,7 @@ static void althold_run()
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // 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); attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
pos_control.set_alt_target_to_current_alt();
}else{ }else{
// call attitude controller // call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());

2
ArduCopter/control_autotune.pde

@ -216,6 +216,7 @@ static void autotune_run()
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -245,6 +246,7 @@ static void autotune_run()
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // 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); attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
pos_control.set_alt_target_to_current_alt();
}else{ }else{
// check if pilot is overriding the controls // check if pilot is overriding the controls
if (target_roll != 0 || target_pitch != 0 || target_yaw_rate != 0.0f || target_climb_rate != 0) { if (target_roll != 0 || target_pitch != 0 || target_yaw_rate != 0.0f || target_climb_rate != 0) {

1
ArduCopter/control_circle.pde

@ -38,6 +38,7 @@ static void circle_run()
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt();
return; return;
} }

2
ArduCopter/control_loiter.pde

@ -38,6 +38,7 @@ static void loiter_run()
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -74,6 +75,7 @@ static void loiter_run()
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // 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); attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
pos_control.set_alt_target_to_current_alt();
}else{ }else{
// run loiter controller // run loiter controller
wp_nav.update_loiter(); wp_nav.update_loiter();

2
ArduCopter/control_ofloiter.pde

@ -37,6 +37,7 @@ static void ofloiter_run()
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt();
reset_optflow_I(); reset_optflow_I();
return; return;
} }
@ -70,6 +71,7 @@ static void ofloiter_run()
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // 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); attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
pos_control.set_alt_target_to_current_alt();
reset_optflow_I(); reset_optflow_I();
}else{ }else{
// mix in user control with optical flow // mix in user control with optical flow

3
ArduCopter/control_poshold.pde

@ -122,7 +122,6 @@ static bool poshold_init(bool ignore_checks)
// set target to current position // set target to current position
// only init here as we can switch to PosHold in flight with a velocity <> 0 that will be used as _last_vel in PosControl and never updated again as we inhibit Reset_I // only init here as we can switch to PosHold in flight with a velocity <> 0 that will be used as _last_vel in PosControl and never updated again as we inhibit Reset_I
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
}else{ }else{
// if not landed start in pilot override to avoid hard twitch // if not landed start in pilot override to avoid hard twitch
poshold.roll_mode = POSHOLD_PILOT_OVERRIDE; poshold.roll_mode = POSHOLD_PILOT_OVERRIDE;
@ -160,6 +159,7 @@ static void poshold_run()
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -190,6 +190,7 @@ static void poshold_run()
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // 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); attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
pos_control.set_alt_target_to_current_alt();
return; return;
}else{ }else{
// convert pilot input to lean angles // convert pilot input to lean angles

2
ArduCopter/control_sport.pde

@ -29,6 +29,7 @@ static void sport_run()
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -80,6 +81,7 @@ static void sport_run()
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // 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); attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
pos_control.set_alt_target_to_current_alt();
}else{ }else{
// call attitude controller // call attitude controller

Loading…
Cancel
Save