mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
Plane: allow set_takeoff_expected in manual mode
This commit is contained in:
parent
740b04aed3
commit
5642d2449a
@ -472,13 +472,8 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle)
|
|||||||
/*
|
/*
|
||||||
setup output channels all non-manual modes
|
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
|
// convert 0 to 100% (or -100 to +100) into PWM
|
||||||
int8_t min_throttle = aparm.throttle_min.get();
|
int8_t min_throttle = aparm.throttle_min.get();
|
||||||
int8_t max_throttle = aparm.throttle_max.get();
|
int8_t max_throttle = aparm.throttle_max.get();
|
||||||
@ -836,9 +831,11 @@ void Plane::set_servos(void)
|
|||||||
|
|
||||||
if (control_mode != &mode_manual) {
|
if (control_mode != &mode_manual) {
|
||||||
set_throttle();
|
set_throttle();
|
||||||
set_takeoff_expected();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Warn AHRS if we might take off soon
|
||||||
|
set_takeoff_expected();
|
||||||
|
|
||||||
// setup flap outputs
|
// setup flap outputs
|
||||||
set_servos_flaps();
|
set_servos_flaps();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user