Copter: payloadplace: avoid using auto_takeoff functionality

Co-authored-by: Leonard Hall <leonardthall@gmail.com>

the methods being called to a lot more than we need or want them to.

In particular, they mix both horizontal and vertical control, but also may or may not run based on various aircraft conditions.

Simplify by simply calling position controller.
This commit is contained in:
Peter Barker 2023-10-05 12:45:16 +11:00 committed by Peter Barker
parent a820612fc9
commit bf59fbc6d9
1 changed files with 14 additions and 6 deletions

View File

@ -1333,16 +1333,21 @@ void PayloadPlace::run()
FALLTHROUGH; FALLTHROUGH;
case State::Ascent_Start: case State::Ascent_Start:
copter.flightmode->auto_takeoff.start(descent_start_altitude_cm, false);
state = State::Ascent; state = State::Ascent;
break; FALLTHROUGH;
case State::Ascent: case State::Ascent: {
if (copter.flightmode->auto_takeoff.complete) { // Ascent complete when we are less than 10% of the stopping
// distance from the target altitude stopping distance from
// vel_threshold_fraction * max velocity
const float vel_threshold_fraction = 0.1;
const float stop_distance = 0.5 * sq(vel_threshold_fraction * copter.pos_control->get_max_speed_up_cms()) / copter.pos_control->get_max_accel_z_cmss();
bool reached_altitude = copter.pos_control->get_pos_target_z_cm() >= descent_start_altitude_cm - stop_distance;
if (reached_altitude) {
state = State::Done; state = State::Done;
} }
break; break;
}
case State::Done: case State::Done:
break; break;
default: default:
@ -1373,7 +1378,10 @@ void PayloadPlace::run()
return; return;
case State::Ascent: case State::Ascent:
case State::Done: case State::Done:
return copter.mode_auto.takeoff_run(); float vel = 0.0;
copter.flightmode->land_run_horizontal_control();
pos_control->input_pos_vel_accel_z(descent_start_altitude_cm, vel, 0.0);
break;
} }
} }