Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: allow takeoff setting expected in manual and move landing override up #25745

Merged
merged 3 commits into from
Dec 12, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -1091,7 +1091,7 @@ class Plane : public AP_Vehicle {
// servos.cpp
void set_servos_idle(void);
void set_servos();
void set_servos_controlled(void);
void set_throttle(void);
void set_takeoff_expected(void);
void set_servos_old_elevons(void);
void set_servos_flaps(void);
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,9 @@ bool Mode::enter()
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "In landing sequence: mission reset");
plane.mission.reset();
}

// Make sure the flight stage is correct for the new mode
plane.update_flight_stage();
}

return enter_result;
Expand Down
18 changes: 10 additions & 8 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -472,13 +472,8 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle)
/*
setup output channels all non-manual modes
*/
void Plane::set_servos_controlled(void)
void Plane::set_throttle(void)
{
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
// allow landing to override servos if it would like to
landing.override_servos();
}

// convert 0 to 100% (or -100 to +100) into PWM
int8_t min_throttle = aparm.throttle_min.get();
int8_t max_throttle = aparm.throttle_max.get();
Expand Down Expand Up @@ -829,11 +824,18 @@ void Plane::set_servos(void)
quadplane.update();
#endif

if (flight_stage == AP_FixedWing::FlightStage::LAND) {
// allow landing to override servos if it would like to
landing.override_servos();
}

if (control_mode != &mode_manual) {
set_servos_controlled();
set_takeoff_expected();
set_throttle();
}

// Warn AHRS if we might take off soon
set_takeoff_expected();

// setup flap outputs
set_servos_flaps();

Expand Down