Copter: Replace set_throttle_takeoff with init_z_controller

This commit is contained in:
Leonard Hall 2022-08-24 21:32:44 +09:30 committed by Randy Mackay
parent 7571ef67af
commit 427c64eff0
5 changed files with 5 additions and 14 deletions

View File

@ -1012,14 +1012,6 @@ GCS_Copter &Mode::gcs()
return copter.gcs();
}
// set_throttle_takeoff - allows modes to tell throttle controller we
// are taking off so I terms can be cleared
void Mode::set_throttle_takeoff()
{
// initialise the vertical position controller
pos_control->init_z_controller();
}
uint16_t Mode::get_pilot_speed_dn()
{
return copter.get_pilot_speed_dn();

View File

@ -296,7 +296,6 @@ public:
bool set_mode(Mode::Number mode, ModeReason reason);
void set_land_complete(bool b);
GCS_Copter &gcs();
void set_throttle_takeoff(void);
uint16_t get_pilot_speed_dn(void);
// end pass-through functions
};

View File

@ -338,7 +338,7 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
auto_yaw.set_mode(AUTO_YAW_HOLD);
// clear i term when we're taking off
set_throttle_takeoff();
pos_control->init_z_controller();
// initialise alt for WP_NAVALT_MIN and set completion alt
auto_takeoff_start(alt_target_cm, alt_target_terrain);

View File

@ -143,7 +143,7 @@ bool ModeGuided::do_user_takeoff_start(float takeoff_alt_cm)
auto_yaw.set_mode(AUTO_YAW_HOLD);
// clear i term when we're taking off
set_throttle_takeoff();
pos_control->init_z_controller();
// initialise alt for WP_NAVALT_MIN and set completion alt
auto_takeoff_start(alt_target_cm, alt_target_terrain);
@ -1042,7 +1042,7 @@ void ModeGuided::angle_control_run()
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
set_land_complete(false);
set_throttle_takeoff();
pos_control->init_z_controller();
}
return;
}

View File

@ -60,7 +60,7 @@ void Mode::_TakeOff::start(float alt_cm)
// indicate we are taking off
copter.set_land_complete(false);
// tell position controller to reset alt target and reset I terms
copter.flightmode->set_throttle_takeoff();
copter.pos_control->init_z_controller();
// initialise takeoff state
_running = true;