Browse Source

Copter: Add missing Loiter initialisation lines.

This command is missing to define the desired acceleration that loiter will initalise to.
loiter_nav->clear_pilot_desired_acceleration();
master
Leonard Hall 6 years ago committed by Randy Mackay
parent
commit
c56acb49d6
  1. 2
      ArduCopter/mode_auto.cpp
  2. 1
      ArduCopter/mode_land.cpp
  3. 3
      ArduCopter/mode_poshold.cpp
  4. 1
      ArduCopter/mode_rtl.cpp

2
ArduCopter/mode_auto.cpp

@ -833,6 +833,7 @@ void ModeAuto::land_run()
// if not armed set throttle to zero and exit immediately // if not armed set throttle to zero and exit immediately
if (is_disarmed_or_landed()) { if (is_disarmed_or_landed()) {
make_safe_spool_down(); make_safe_spool_down();
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
return; return;
} }
@ -928,6 +929,7 @@ void ModeAuto::loiter_to_alt_run()
} }
if (!loiter_to_alt.loiter_start_done) { if (!loiter_to_alt.loiter_start_done) {
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
_mode = Auto_LoiterToAlt; _mode = Auto_LoiterToAlt;
loiter_to_alt.loiter_start_done = true; loiter_to_alt.loiter_start_done = true;

1
ArduCopter/mode_land.cpp

@ -61,6 +61,7 @@ void ModeLand::gps_run()
// Land State Machine Determination // Land State Machine Determination
if (is_disarmed_or_landed()) { if (is_disarmed_or_landed()) {
make_safe_spool_down(); make_safe_spool_down();
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
} else { } else {
// set motors to full range // set motors to full range

3
ArduCopter/mode_poshold.cpp

@ -111,6 +111,7 @@ void ModePosHold::run()
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
loiter_nav->update(); loiter_nav->update();
@ -133,6 +134,7 @@ void ModePosHold::run()
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
// init and update loiter although pilot is controlling lean angles // init and update loiter although pilot is controlling lean angles
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
loiter_nav->update(); loiter_nav->update();
@ -147,6 +149,7 @@ void ModePosHold::run()
case AltHold_Landed_Ground_Idle: case AltHold_Landed_Ground_Idle:
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
loiter_nav->update(); loiter_nav->update();
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();

1
ArduCopter/mode_rtl.cpp

@ -384,6 +384,7 @@ void ModeRTL::land_run(bool disarm_on_land)
// if not armed set throttle to zero and exit immediately // if not armed set throttle to zero and exit immediately
if (is_disarmed_or_landed()) { if (is_disarmed_or_landed()) {
make_safe_spool_down(); make_safe_spool_down();
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
return; return;
} }

Loading…
Cancel
Save