Copter: payloadplace: fold methods back into caller

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

these methods don't really add much, and prohibit future refactoring
This commit is contained in:
Peter Barker 2023-10-05 12:12:10 +11:00 committed by Peter Barker
parent af949590f8
commit a820612fc9
2 changed files with 10 additions and 24 deletions

View File

@ -52,8 +52,6 @@ public:
float descent_max_cm;
private:
void run_hover();
void run_descent();
uint32_t descent_established_time_ms; // milliseconds
uint32_t place_start_time_ms; // milliseconds

View File

@ -1357,36 +1357,24 @@ void PayloadPlace::run()
return copter.mode_auto.wp_run();
case State::Descent_Start:
case State::Descent:
return run_descent();
case State::Release:
case State::Releasing:
case State::Delay:
case State::Ascent_Start:
return run_hover();
case State::Ascent:
case State::Done:
return copter.mode_auto.takeoff_run();
}
}
void PayloadPlace::run_hover()
{
const auto &pos_control = copter.pos_control;
copter.flightmode->land_run_horizontal_control();
// update altitude target and call position controller
pos_control->land_at_climb_rate_cm(0.0, false);
pos_control->update_z_controller();
}
void PayloadPlace::run_descent()
{
const auto &pos_control = copter.pos_control;
copter.flightmode->land_run_horizontal_control();
// update altitude target and call position controller
pos_control->land_at_climb_rate_cm(-descent_speed_cms, true);
pos_control->update_z_controller();
return;
case State::Release:
case State::Releasing:
case State::Delay:
case State::Ascent_Start:
copter.flightmode->land_run_horizontal_control();
// update altitude target and call position controller
pos_control->land_at_climb_rate_cm(0.0, false);
pos_control->update_z_controller();
return;
case State::Ascent:
case State::Done:
return copter.mode_auto.takeoff_run();
}
}
// sets the target_loc's alt to the vehicle's current alt but does not change target_loc's frame