mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
Copter: have takeoff.start() handle clearing i terms and setting land-complete
This commit is contained in:
parent
479c238177
commit
3c436b30f0
@ -70,10 +70,6 @@ void Copter::ModeAltHold::run()
|
||||
// initiate take-off
|
||||
if (!takeoff.running()) {
|
||||
takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
|
||||
// indicate we are taking off
|
||||
set_land_complete(false);
|
||||
// clear i terms
|
||||
set_throttle_takeoff();
|
||||
}
|
||||
|
||||
// get take-off adjusted pilot and takeoff climb rates
|
||||
|
@ -269,10 +269,6 @@ void Copter::ModeFlowHold::run()
|
||||
// initiate take-off
|
||||
if (!takeoff.running()) {
|
||||
takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
|
||||
// indicate we are taking off
|
||||
copter.set_land_complete(false);
|
||||
// clear i terms
|
||||
copter.set_throttle_takeoff();
|
||||
}
|
||||
|
||||
// get take-off adjusted pilot and takeoff climb rates
|
||||
|
@ -131,10 +131,6 @@ void Copter::ModeLoiter::run()
|
||||
// initiate take-off
|
||||
if (!takeoff.running()) {
|
||||
takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
|
||||
// indicate we are taking off
|
||||
set_land_complete(false);
|
||||
// clear i term when we're taking off
|
||||
set_throttle_takeoff();
|
||||
}
|
||||
|
||||
// get takeoff adjusted pilot and takeoff climb rates
|
||||
|
@ -124,10 +124,6 @@ void Copter::ModePosHold::run()
|
||||
// initiate take-off
|
||||
if (!takeoff.running()) {
|
||||
takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
|
||||
// indicate we are taking off
|
||||
set_land_complete(false);
|
||||
// clear i terms
|
||||
set_throttle_takeoff();
|
||||
}
|
||||
|
||||
// get take-off adjusted pilot and takeoff climb rates
|
||||
|
@ -90,10 +90,6 @@ void Copter::ModeSport::run()
|
||||
// initiate take-off
|
||||
if (!takeoff.running()) {
|
||||
takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
|
||||
// indicate we are taking off
|
||||
set_land_complete(false);
|
||||
// clear i terms
|
||||
set_throttle_takeoff();
|
||||
}
|
||||
|
||||
// get take-off adjusted pilot and takeoff climb rates
|
||||
|
@ -48,11 +48,16 @@ bool Copter::Mode::do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
|
||||
// start takeoff to specified altitude above home in centimeters
|
||||
void Copter::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.set_throttle_takeoff();
|
||||
|
||||
// calculate climb rate
|
||||
const float speed = MIN(copter.wp_nav->get_default_speed_up(), MAX(copter.g.pilot_speed_up*2.0f/3.0f, copter.g.pilot_speed_up-50.0f));
|
||||
|
||||
// sanity check speed and target
|
||||
if (running() || speed <= 0.0f || alt_cm <= 0.0f) {
|
||||
if (speed <= 0.0f || alt_cm <= 0.0f) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user