mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: Replace set_throttle_takeoff with init_z_controller
This commit is contained in:
parent
7571ef67af
commit
427c64eff0
@ -1012,14 +1012,6 @@ GCS_Copter &Mode::gcs()
|
|||||||
return copter.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()
|
uint16_t Mode::get_pilot_speed_dn()
|
||||||
{
|
{
|
||||||
return copter.get_pilot_speed_dn();
|
return copter.get_pilot_speed_dn();
|
||||||
|
@ -203,7 +203,7 @@ protected:
|
|||||||
private:
|
private:
|
||||||
bool _running;
|
bool _running;
|
||||||
float take_off_start_alt;
|
float take_off_start_alt;
|
||||||
float take_off_complete_alt ;
|
float take_off_complete_alt;
|
||||||
};
|
};
|
||||||
|
|
||||||
static _TakeOff takeoff;
|
static _TakeOff takeoff;
|
||||||
@ -296,7 +296,6 @@ public:
|
|||||||
bool set_mode(Mode::Number mode, ModeReason reason);
|
bool set_mode(Mode::Number mode, ModeReason reason);
|
||||||
void set_land_complete(bool b);
|
void set_land_complete(bool b);
|
||||||
GCS_Copter &gcs();
|
GCS_Copter &gcs();
|
||||||
void set_throttle_takeoff(void);
|
|
||||||
uint16_t get_pilot_speed_dn(void);
|
uint16_t get_pilot_speed_dn(void);
|
||||||
// end pass-through functions
|
// end pass-through functions
|
||||||
};
|
};
|
||||||
|
@ -338,7 +338,7 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
|
|||||||
auto_yaw.set_mode(AUTO_YAW_HOLD);
|
auto_yaw.set_mode(AUTO_YAW_HOLD);
|
||||||
|
|
||||||
// clear i term when we're taking off
|
// 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
|
// initialise alt for WP_NAVALT_MIN and set completion alt
|
||||||
auto_takeoff_start(alt_target_cm, alt_target_terrain);
|
auto_takeoff_start(alt_target_cm, alt_target_terrain);
|
||||||
|
@ -143,7 +143,7 @@ bool ModeGuided::do_user_takeoff_start(float takeoff_alt_cm)
|
|||||||
auto_yaw.set_mode(AUTO_YAW_HOLD);
|
auto_yaw.set_mode(AUTO_YAW_HOLD);
|
||||||
|
|
||||||
// clear i term when we're taking off
|
// 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
|
// initialise alt for WP_NAVALT_MIN and set completion alt
|
||||||
auto_takeoff_start(alt_target_cm, alt_target_terrain);
|
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);
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||||
if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
|
if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
|
||||||
set_land_complete(false);
|
set_land_complete(false);
|
||||||
set_throttle_takeoff();
|
pos_control->init_z_controller();
|
||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -60,7 +60,7 @@ void Mode::_TakeOff::start(float alt_cm)
|
|||||||
// indicate we are taking off
|
// indicate we are taking off
|
||||||
copter.set_land_complete(false);
|
copter.set_land_complete(false);
|
||||||
// tell position controller to reset alt target and reset I terms
|
// 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
|
// initialise takeoff state
|
||||||
_running = true;
|
_running = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user