mirror of https://github.com/ArduPilot/ardupilot
Plane:remove duplication in setting servos in MANUAL
This commit is contained in:
parent
bbcc31ecec
commit
3f7f7cd3a1
|
@ -1089,7 +1089,6 @@ private:
|
|||
// servos.cpp
|
||||
void set_servos_idle(void);
|
||||
void set_servos();
|
||||
void set_servos_manual_passthrough(void);
|
||||
void set_servos_controlled(void);
|
||||
void set_servos_old_elevons(void);
|
||||
void set_servos_flaps(void);
|
||||
|
|
|
@ -5,7 +5,26 @@ void ModeManual::update()
|
|||
{
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.roll_in_expo(false));
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, plane.pitch_in_expo(false));
|
||||
//rudder in sets rudder, but is also assigned to steering values used later in servos.cpp for steering
|
||||
plane.steering_control.steering = plane.steering_control.rudder = plane.rudder_in_expo(false);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, plane.steering_control.steering);
|
||||
float throttle = plane.get_throttle_input(true);
|
||||
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
if (quadplane.available() && quadplane.option_is_set(QuadPlane::OPTION::IDLE_GOV_MANUAL)) {
|
||||
// for quadplanes it can be useful to run the idle governor in MANUAL mode
|
||||
// as it prevents the VTOL motors from running
|
||||
int8_t min_throttle = plane.aparm.throttle_min.get();
|
||||
|
||||
// apply idle governor
|
||||
#if AP_ICENGINE_ENABLED
|
||||
plane.g2.ice_control.update_idle_governor(min_throttle);
|
||||
#endif
|
||||
throttle = MAX(throttle, min_throttle);
|
||||
}
|
||||
#endif
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle);
|
||||
|
||||
plane.nav_roll_cd = ahrs.roll_sensor;
|
||||
plane.nav_pitch_cd = ahrs.pitch_sensor;
|
||||
|
|
|
@ -47,6 +47,7 @@ public:
|
|||
friend class Tailsitter_Transition;
|
||||
|
||||
friend class Mode;
|
||||
friend class ModeManual;
|
||||
friend class ModeAuto;
|
||||
friend class ModeRTL;
|
||||
friend class ModeAvoidADSB;
|
||||
|
|
|
@ -376,32 +376,6 @@ void Plane::set_servos_idle(void)
|
|||
SRV_Channels::output_ch_all();
|
||||
}
|
||||
|
||||
/*
|
||||
pass through channels in manual mode
|
||||
*/
|
||||
void Plane::set_servos_manual_passthrough(void)
|
||||
{
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, roll_in_expo(false));
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, pitch_in_expo(false));
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_in_expo(false));
|
||||
float throttle = get_throttle_input(true);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle);
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
if (quadplane.available() && quadplane.option_is_set(QuadPlane::OPTION::IDLE_GOV_MANUAL)) {
|
||||
// for quadplanes it can be useful to run the idle governor in MANUAL mode
|
||||
// as it prevents the VTOL motors from running
|
||||
int8_t min_throttle = aparm.throttle_min.get();
|
||||
|
||||
// apply idle governor
|
||||
#if AP_ICENGINE_ENABLED
|
||||
g2.ice_control.update_idle_governor(min_throttle);
|
||||
#endif
|
||||
throttle = MAX(throttle, min_throttle);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
Scale the throttle to conpensate for battery voltage drop
|
||||
|
@ -870,9 +844,7 @@ void Plane::set_servos(void)
|
|||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_control.rudder);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_control.steering);
|
||||
|
||||
if (control_mode == &mode_manual) {
|
||||
set_servos_manual_passthrough();
|
||||
} else {
|
||||
if (control_mode != &mode_manual) {
|
||||
set_servos_controlled();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue