Browse Source

Copter: minor formatting fixes

mission-4.1.18
Randy Mackay 10 years ago
parent
commit
05fedbf98f
  1. 4
      ArduCopter/control_auto.pde
  2. 6
      ArduCopter/control_land.pde
  3. 1
      ArduCopter/control_rtl.pde

4
ArduCopter/control_auto.pde

@ -323,12 +323,12 @@ static void auto_land_run() @@ -323,12 +323,12 @@ static void auto_land_run()
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
float cmb_rate = get_land_descent_speed();
// call z-axis position controller
float cmb_rate = get_land_descent_speed();
pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true);
pos_control.update_z_controller();
// record desired climb rate for logging
desired_climb_rate = cmb_rate;
// roll & pitch from waypoint controller, yaw rate from pilot

6
ArduCopter/control_land.pde

@ -102,7 +102,7 @@ static void land_gps_run() @@ -102,7 +102,7 @@ static void land_gps_run()
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
//pause 4 seconds before beginning land descent
// pause 4 seconds before beginning land descent
float cmb_rate;
if(land_pause && millis()-land_start_time < 4000) {
cmb_rate = 0;
@ -111,6 +111,7 @@ static void land_gps_run() @@ -111,6 +111,7 @@ static void land_gps_run()
cmb_rate = get_land_descent_speed();
}
// record desired climb rate for logging
desired_climb_rate = cmb_rate;
// update altitude target and call position controller
@ -162,7 +163,7 @@ static void land_nogps_run() @@ -162,7 +163,7 @@ static void land_nogps_run()
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
//pause 4 seconds before beginning land descent
// pause 4 seconds before beginning land descent
float cmb_rate;
if(land_pause && millis()-land_start_time < LAND_WITH_DELAY_MS) {
cmb_rate = 0;
@ -171,6 +172,7 @@ static void land_nogps_run() @@ -171,6 +172,7 @@ static void land_nogps_run()
cmb_rate = get_land_descent_speed();
}
// record desired climb rate for logging
desired_climb_rate = cmb_rate;
// call position controller

1
ArduCopter/control_rtl.pde

@ -380,6 +380,7 @@ static void rtl_land_run() @@ -380,6 +380,7 @@ static void rtl_land_run()
pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true);
pos_control.update_z_controller();
// record desired climb rate for logging
desired_climb_rate = cmb_rate;
// roll & pitch from waypoint controller, yaw rate from pilot

Loading…
Cancel
Save