2016-10-09 04:58:31 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
main logic for servo control
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "Plane.h"
|
2016-11-30 00:49:32 -04:00
|
|
|
#include <utility>
|
2016-10-09 04:58:31 -03:00
|
|
|
|
|
|
|
/*****************************************
|
|
|
|
* Throttle slew limit
|
|
|
|
*****************************************/
|
2016-10-22 07:27:57 -03:00
|
|
|
void Plane::throttle_slew_limit(void)
|
2016-10-09 04:58:31 -03:00
|
|
|
{
|
|
|
|
uint8_t slewrate = aparm.throttle_slewrate;
|
|
|
|
if (control_mode==AUTO) {
|
|
|
|
if (auto_state.takeoff_complete == false && g.takeoff_throttle_slewrate != 0) {
|
|
|
|
slewrate = g.takeoff_throttle_slewrate;
|
2017-01-11 01:29:03 -04:00
|
|
|
} else if (landing.get_throttle_slewrate() != 0 && flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
2016-11-23 06:18:21 -04:00
|
|
|
slewrate = landing.get_throttle_slewrate();
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
// if slew limit rate is set to zero then do not slew limit
|
|
|
|
if (slewrate) {
|
2017-01-07 02:14:08 -04:00
|
|
|
SRV_Channels::limit_slew_rate(SRV_Channel::k_throttle, slewrate, G_Dt);
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/* We want to suppress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
|
|
|
|
|
|
|
|
Disable throttle if following conditions are met:
|
|
|
|
* 1 - We are in Circle mode (which we use for short term failsafe), or in FBW-B or higher
|
|
|
|
* AND
|
|
|
|
* 2 - Our reported altitude is within 10 meters of the home altitude.
|
|
|
|
* 3 - Our reported speed is under 5 meters per second.
|
|
|
|
* 4 - We are not performing a takeoff in Auto mode or takeoff speed/accel not yet reached
|
|
|
|
* OR
|
|
|
|
* 5 - Home location is not set
|
2017-02-14 15:13:11 -04:00
|
|
|
* OR
|
|
|
|
* 6- Landing does not want to allow throttle
|
2016-10-09 04:58:31 -03:00
|
|
|
*/
|
|
|
|
bool Plane::suppress_throttle(void)
|
|
|
|
{
|
|
|
|
#if PARACHUTE == ENABLED
|
|
|
|
if (auto_throttle_mode && parachute.release_initiated()) {
|
|
|
|
// throttle always suppressed in auto-throttle modes after parachute release initiated
|
|
|
|
throttle_suppressed = true;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2017-02-14 15:13:11 -04:00
|
|
|
if (landing.is_throttle_suppressed()) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-10-09 04:58:31 -03:00
|
|
|
if (!throttle_suppressed) {
|
|
|
|
// we've previously met a condition for unsupressing the throttle
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (!auto_throttle_mode) {
|
|
|
|
// the user controls the throttle
|
|
|
|
throttle_suppressed = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (control_mode==AUTO && g.auto_fbw_steer == 42) {
|
|
|
|
// user has throttle control
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool gps_movement = (gps.status() >= AP_GPS::GPS_OK_FIX_2D && gps.ground_speed() >= 5);
|
|
|
|
|
|
|
|
if (control_mode==AUTO &&
|
|
|
|
auto_state.takeoff_complete == false) {
|
|
|
|
|
|
|
|
uint32_t launch_duration_ms = ((int32_t)g.takeoff_throttle_delay)*100 + 2000;
|
|
|
|
if (is_flying() &&
|
|
|
|
millis() - started_flying_ms > MAX(launch_duration_ms, 5000U) && // been flying >5s in any mode
|
|
|
|
adjusted_relative_altitude_cm() > 500 && // are >5m above AGL/home
|
|
|
|
labs(ahrs.pitch_sensor) < 3000 && // not high pitch, which happens when held before launch
|
|
|
|
gps_movement) { // definite gps movement
|
|
|
|
// we're already flying, do not suppress the throttle. We can get
|
|
|
|
// stuck in this condition if we reset a mission and cmd 1 is takeoff
|
|
|
|
// but we're currently flying around below the takeoff altitude
|
|
|
|
throttle_suppressed = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (auto_takeoff_check()) {
|
|
|
|
// we're in auto takeoff
|
|
|
|
throttle_suppressed = false;
|
|
|
|
auto_state.baro_takeoff_alt = barometer.get_altitude();
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// keep throttle suppressed
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-01-30 15:48:22 -04:00
|
|
|
if (fabsf(relative_altitude) >= 10.0f) {
|
2016-10-09 04:58:31 -03:00
|
|
|
// we're more than 10m from the home altitude
|
|
|
|
throttle_suppressed = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (gps_movement) {
|
|
|
|
// if we have an airspeed sensor, then check it too, and
|
|
|
|
// require 5m/s. This prevents throttle up due to spiky GPS
|
|
|
|
// groundspeed with bad GPS reception
|
|
|
|
if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) {
|
|
|
|
// we're moving at more than 5 m/s
|
|
|
|
throttle_suppressed = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (quadplane.is_flying()) {
|
|
|
|
throttle_suppressed = false;
|
2016-10-16 19:49:55 -03:00
|
|
|
return false;
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// throttle remains suppressed
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
implement a software VTail or elevon mixer. There are 4 different mixing modes
|
|
|
|
*/
|
2016-10-22 07:27:57 -03:00
|
|
|
void Plane::channel_output_mixer_pwm(uint8_t mixing_type, uint16_t & chan1_out, uint16_t & chan2_out) const
|
2016-10-09 04:58:31 -03:00
|
|
|
{
|
|
|
|
int16_t c1, c2;
|
|
|
|
int16_t v1, v2;
|
|
|
|
|
|
|
|
// first get desired elevator and rudder as -500..500 values
|
|
|
|
c1 = chan1_out - 1500;
|
|
|
|
c2 = chan2_out - 1500;
|
|
|
|
|
|
|
|
// apply MIXING_OFFSET to input channels using long-integer version
|
|
|
|
// of formula: x = x * (g.mixing_offset/100.0 + 1.0)
|
|
|
|
// -100 => 2x on 'c1', 100 => 2x on 'c2'
|
|
|
|
if (g.mixing_offset < 0) {
|
|
|
|
c1 = (int16_t)(((int32_t)c1) * (-g.mixing_offset+100) / 100);
|
|
|
|
} else if (g.mixing_offset > 0) {
|
|
|
|
c2 = (int16_t)(((int32_t)c2) * (g.mixing_offset+100) / 100);
|
|
|
|
}
|
|
|
|
|
|
|
|
v1 = (c1 - c2) * g.mixing_gain;
|
|
|
|
v2 = (c1 + c2) * g.mixing_gain;
|
|
|
|
|
|
|
|
// now map to mixed output
|
|
|
|
switch (mixing_type) {
|
|
|
|
case MIXING_DISABLED:
|
|
|
|
return;
|
|
|
|
|
|
|
|
case MIXING_UPUP:
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MIXING_UPDN:
|
|
|
|
v2 = -v2;
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MIXING_DNUP:
|
|
|
|
v1 = -v1;
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MIXING_DNDN:
|
|
|
|
v1 = -v1;
|
|
|
|
v2 = -v2;
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MIXING_UPUP_SWP:
|
|
|
|
std::swap(v1, v2);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MIXING_UPDN_SWP:
|
|
|
|
v2 = -v2;
|
|
|
|
std::swap(v1, v2);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MIXING_DNUP_SWP:
|
|
|
|
v1 = -v1;
|
|
|
|
std::swap(v1, v2);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MIXING_DNDN_SWP:
|
|
|
|
v1 = -v1;
|
|
|
|
v2 = -v2;
|
|
|
|
std::swap(v1, v2);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// scale for a 1500 center and 900..2100 range, symmetric
|
|
|
|
v1 = constrain_int16(v1, -600, 600);
|
|
|
|
v2 = constrain_int16(v2, -600, 600);
|
|
|
|
|
|
|
|
chan1_out = 1500 + v1;
|
|
|
|
chan2_out = 1500 + v2;
|
|
|
|
}
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
/*
|
|
|
|
output mixer based on two channel output types
|
|
|
|
*/
|
|
|
|
void Plane::channel_output_mixer(uint8_t mixing_type, SRV_Channel::Aux_servo_function_t func1, SRV_Channel::Aux_servo_function_t func2)
|
2016-10-09 04:58:31 -03:00
|
|
|
{
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channel *chan1, *chan2;
|
|
|
|
if (!(chan1 = SRV_Channels::get_channel_for(func1)) ||
|
|
|
|
!(chan2 = SRV_Channels::get_channel_for(func2))) {
|
|
|
|
return;
|
|
|
|
}
|
2016-10-09 04:58:31 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
uint16_t chan1_out, chan2_out;
|
|
|
|
chan1_out = chan1->get_output_pwm();
|
|
|
|
chan2_out = chan2->get_output_pwm();
|
|
|
|
|
|
|
|
channel_output_mixer_pwm(mixing_type, chan1_out, chan2_out);
|
2016-10-09 04:58:31 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
chan1->set_output_pwm(chan1_out);
|
|
|
|
chan2->set_output_pwm(chan2_out);
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
|
2016-10-09 04:58:31 -03:00
|
|
|
/*
|
|
|
|
setup flaperon output channels
|
|
|
|
*/
|
|
|
|
void Plane::flaperon_update(int8_t flap_percent)
|
|
|
|
{
|
2016-10-22 07:27:57 -03:00
|
|
|
if (!SRV_Channels::function_assigned(SRV_Channel::k_flaperon1) ||
|
|
|
|
!SRV_Channels::function_assigned(SRV_Channel::k_flaperon2)) {
|
2016-10-09 04:58:31 -03:00
|
|
|
return;
|
|
|
|
}
|
2016-10-22 07:27:57 -03:00
|
|
|
uint16_t ch1, ch2;
|
2016-10-09 04:58:31 -03:00
|
|
|
/*
|
|
|
|
flaperons are implemented as a mixer between aileron and a
|
|
|
|
percentage of flaps. Flap input can come from a manual channel
|
|
|
|
or from auto flaps.
|
|
|
|
|
|
|
|
Use k_flaperon1 and k_flaperon2 channel trims to center servos.
|
|
|
|
Then adjust aileron trim for level flight (note that aileron trim is affected
|
|
|
|
by mixing gain). flapin_channel's trim is not used.
|
|
|
|
*/
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
if (!SRV_Channels::get_output_pwm(SRV_Channel::k_aileron, ch1)) {
|
|
|
|
return;
|
|
|
|
}
|
2016-10-09 04:58:31 -03:00
|
|
|
// The *5 is to take a percentage to a value from -500 to 500 for the mixer
|
|
|
|
ch2 = 1500 - flap_percent * 5;
|
2016-10-22 07:27:57 -03:00
|
|
|
channel_output_mixer_pwm(g.flaperon_output, ch1, ch2);
|
|
|
|
SRV_Channels::set_output_pwm_trimmed(SRV_Channel::k_flaperon1, ch1);
|
|
|
|
SRV_Channels::set_output_pwm_trimmed(SRV_Channel::k_flaperon2, ch2);
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
setup servos for idle mode
|
|
|
|
Idle mode is used during balloon launch to keep servos still, apart
|
|
|
|
from occasional wiggle to prevent freezing up
|
|
|
|
*/
|
|
|
|
void Plane::set_servos_idle(void)
|
|
|
|
{
|
|
|
|
if (auto_state.idle_wiggle_stage == 0) {
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::output_trim_all();
|
2016-10-09 04:58:31 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
int16_t servo_value = 0;
|
|
|
|
// move over full range for 2 seconds
|
|
|
|
auto_state.idle_wiggle_stage += 2;
|
|
|
|
if (auto_state.idle_wiggle_stage < 50) {
|
|
|
|
servo_value = auto_state.idle_wiggle_stage * (4500 / 50);
|
|
|
|
} else if (auto_state.idle_wiggle_stage < 100) {
|
|
|
|
servo_value = (100 - auto_state.idle_wiggle_stage) * (4500 / 50);
|
|
|
|
} else if (auto_state.idle_wiggle_stage < 150) {
|
|
|
|
servo_value = (100 - auto_state.idle_wiggle_stage) * (4500 / 50);
|
|
|
|
} else if (auto_state.idle_wiggle_stage < 200) {
|
|
|
|
servo_value = (auto_state.idle_wiggle_stage-200) * (4500 / 50);
|
|
|
|
} else {
|
|
|
|
auto_state.idle_wiggle_stage = 0;
|
|
|
|
}
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, servo_value);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, servo_value);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, servo_value);
|
|
|
|
SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle);
|
2016-10-09 04:58:31 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::output_ch_all();
|
|
|
|
}
|
2016-10-09 04:58:31 -03:00
|
|
|
|
2016-10-09 05:14:17 -03:00
|
|
|
/*
|
|
|
|
pass through channels in manual mode
|
|
|
|
*/
|
|
|
|
void Plane::set_servos_manual_passthrough(void)
|
|
|
|
{
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, channel_roll->get_control_in_zero_dz());
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, channel_pitch->get_control_in_zero_dz());
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, channel_rudder->get_control_in_zero_dz());
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in_zero_dz());
|
2016-10-09 05:14:17 -03:00
|
|
|
|
|
|
|
// this variant assumes you have the corresponding
|
|
|
|
// input channel setup in your transmitter for manual control
|
|
|
|
// of the 2nd aileron
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::copy_radio_in_out(SRV_Channel::k_aileron_with_input);
|
|
|
|
SRV_Channels::copy_radio_in_out(SRV_Channel::k_elevator_with_input);
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
old (deprecated) elevon support
|
|
|
|
*/
|
|
|
|
void Plane::set_servos_old_elevons(void)
|
|
|
|
{
|
|
|
|
/*Elevon mode*/
|
|
|
|
float ch1;
|
|
|
|
float ch2;
|
2016-10-22 07:27:57 -03:00
|
|
|
int16_t roll = SRV_Channels::get_output_scaled(SRV_Channel::k_aileron);
|
|
|
|
int16_t pitch = SRV_Channels::get_output_scaled(SRV_Channel::k_elevator);
|
|
|
|
ch1 = pitch - (BOOL_TO_SIGN(g.reverse_elevons) * roll);
|
|
|
|
ch2 = pitch + (BOOL_TO_SIGN(g.reverse_elevons) * roll);
|
2016-10-09 05:14:17 -03:00
|
|
|
|
|
|
|
/* Differential Spoilers
|
|
|
|
If differential spoilers are setup, then we translate
|
|
|
|
rudder control into splitting of the two ailerons on
|
|
|
|
the side of the aircraft where we want to induce
|
|
|
|
additional drag.
|
|
|
|
*/
|
2016-10-22 07:27:57 -03:00
|
|
|
if (SRV_Channels::function_assigned(SRV_Channel::k_dspoiler1) && SRV_Channels::function_assigned(SRV_Channel::k_dspoiler2)) {
|
2016-10-09 05:14:17 -03:00
|
|
|
float ch3 = ch1;
|
|
|
|
float ch4 = ch2;
|
2016-10-22 07:27:57 -03:00
|
|
|
int16_t rudder = SRV_Channels::get_output_scaled(SRV_Channel::k_rudder);
|
|
|
|
if (BOOL_TO_SIGN(g.reverse_elevons) * rudder < 0) {
|
|
|
|
ch1 += abs(rudder);
|
|
|
|
ch3 -= abs(rudder);
|
2016-10-09 05:14:17 -03:00
|
|
|
} else {
|
2016-10-22 07:27:57 -03:00
|
|
|
ch2 += abs(rudder);
|
|
|
|
ch4 -= abs(rudder);
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoiler1, ch3);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoiler2, ch4);
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// directly set the radio_out values for elevon mode
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_pwm_first(SRV_Channel::k_aileron, elevon.trim1 + (BOOL_TO_SIGN(g.reverse_ch1_elevon) * (ch1 * 500.0f/ SERVO_MAX)));
|
|
|
|
SRV_Channels::set_output_pwm_first(SRV_Channel::k_elevator, elevon.trim2 + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0f/ SERVO_MAX)));
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
calculate any throttle limits based on the watt limiter
|
|
|
|
*/
|
|
|
|
void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle)
|
|
|
|
{
|
|
|
|
uint32_t now = millis();
|
|
|
|
if (battery.overpower_detected()) {
|
|
|
|
// overpower detected, cut back on the throttle if we're maxing it out by calculating a limiter value
|
|
|
|
// throttle limit will attack by 10% per second
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
if (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > 0 && // demanding too much positive thrust
|
2016-10-09 05:14:17 -03:00
|
|
|
throttle_watt_limit_max < max_throttle - 25 &&
|
|
|
|
now - throttle_watt_limit_timer_ms >= 1) {
|
|
|
|
// always allow for 25% throttle available regardless of battery status
|
|
|
|
throttle_watt_limit_timer_ms = now;
|
|
|
|
throttle_watt_limit_max++;
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
} else if (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) < 0 &&
|
2016-10-09 05:14:17 -03:00
|
|
|
min_throttle < 0 && // reverse thrust is available
|
|
|
|
throttle_watt_limit_min < -(min_throttle) - 25 &&
|
|
|
|
now - throttle_watt_limit_timer_ms >= 1) {
|
|
|
|
// always allow for 25% throttle available regardless of battery status
|
|
|
|
throttle_watt_limit_timer_ms = now;
|
|
|
|
throttle_watt_limit_min++;
|
|
|
|
}
|
|
|
|
|
|
|
|
} else if (now - throttle_watt_limit_timer_ms >= 1000) {
|
|
|
|
// it has been 1 second since last over-current, check if we can resume higher throttle.
|
|
|
|
// this throttle release is needed to allow raising the max_throttle as the battery voltage drains down
|
|
|
|
// throttle limit will release by 1% per second
|
2016-10-22 07:27:57 -03:00
|
|
|
if (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > throttle_watt_limit_max && // demanding max forward thrust
|
2016-10-09 05:14:17 -03:00
|
|
|
throttle_watt_limit_max > 0) { // and we're currently limiting it
|
|
|
|
throttle_watt_limit_timer_ms = now;
|
|
|
|
throttle_watt_limit_max--;
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
} else if (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) < throttle_watt_limit_min && // demanding max negative thrust
|
2016-10-09 05:14:17 -03:00
|
|
|
throttle_watt_limit_min > 0) { // and we're limiting it
|
|
|
|
throttle_watt_limit_timer_ms = now;
|
|
|
|
throttle_watt_limit_min--;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
max_throttle = constrain_int16(max_throttle, 0, max_throttle - throttle_watt_limit_max);
|
|
|
|
if (min_throttle < 0) {
|
|
|
|
min_throttle = constrain_int16(min_throttle, min_throttle + throttle_watt_limit_min, 0);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
setup output channels all non-manual modes
|
|
|
|
*/
|
|
|
|
void Plane::set_servos_controlled(void)
|
|
|
|
{
|
|
|
|
if (g.mix_mode != 0) {
|
|
|
|
set_servos_old_elevons();
|
|
|
|
} else {
|
|
|
|
// both types of secondary aileron are slaved to the roll servo out
|
2017-02-14 15:20:47 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron_with_input,
|
|
|
|
SRV_Channels::get_output_scaled(SRV_Channel::k_aileron));
|
|
|
|
|
2016-10-09 05:14:17 -03:00
|
|
|
// both types of secondary elevator are slaved to the pitch servo out
|
2017-02-14 15:20:47 -04:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator_with_input,
|
|
|
|
SRV_Channels::get_output_scaled(SRV_Channel::k_elevator));
|
|
|
|
}
|
|
|
|
|
|
|
|
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
|
|
|
// allow landing to override servos if it would like to
|
|
|
|
landing.override_servos();
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// 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();
|
|
|
|
|
|
|
|
if (min_throttle < 0 && !allow_reverse_thrust()) {
|
|
|
|
// reverse thrust is available but inhibited.
|
|
|
|
min_throttle = 0;
|
|
|
|
}
|
|
|
|
|
2017-01-10 03:42:57 -04:00
|
|
|
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
|
|
|
|
if(aparm.takeoff_throttle_max != 0) {
|
|
|
|
max_throttle = aparm.takeoff_throttle_max;
|
|
|
|
} else {
|
|
|
|
max_throttle = aparm.throttle_max;
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
2017-01-10 03:42:57 -04:00
|
|
|
} else if (landing.is_flaring()) {
|
|
|
|
min_throttle = 0;
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
2016-10-22 07:27:57 -03:00
|
|
|
|
2016-10-09 05:14:17 -03:00
|
|
|
// apply watt limiter
|
|
|
|
throttle_watt_limiter(min_throttle, max_throttle);
|
2016-10-22 07:27:57 -03:00
|
|
|
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle,
|
|
|
|
constrain_int16(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), min_throttle, max_throttle));
|
2016-10-09 05:14:17 -03:00
|
|
|
|
|
|
|
if (!hal.util->get_soft_armed()) {
|
2016-10-22 07:27:57 -03:00
|
|
|
if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) {
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
|
|
|
} else {
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0);
|
|
|
|
}
|
2016-10-09 05:14:17 -03:00
|
|
|
} else if (suppress_throttle()) {
|
|
|
|
// throttle is suppressed in auto mode
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0);
|
2016-10-09 05:14:17 -03:00
|
|
|
if (g.throttle_suppress_manual) {
|
|
|
|
// manual pass through of throttle while throttle is suppressed
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in_zero_dz());
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
|
|
|
} else if (g.throttle_passthru_stabilize &&
|
|
|
|
(control_mode == STABILIZE ||
|
|
|
|
control_mode == TRAINING ||
|
|
|
|
control_mode == ACRO ||
|
|
|
|
control_mode == FLY_BY_WIRE_A ||
|
|
|
|
control_mode == AUTOTUNE) &&
|
|
|
|
!failsafe.ch3_counter) {
|
|
|
|
// manual pass through of throttle while in FBWA or
|
|
|
|
// STABILIZE mode with THR_PASS_STAB set
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in_zero_dz());
|
2016-10-09 05:14:17 -03:00
|
|
|
} else if ((control_mode == GUIDED || control_mode == AVOID_ADSB) &&
|
|
|
|
guided_throttle_passthru) {
|
|
|
|
// manual pass through of throttle while in GUIDED
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in_zero_dz());
|
2016-10-09 05:14:17 -03:00
|
|
|
} else if (quadplane.in_vtol_mode()) {
|
|
|
|
// ask quadplane code for forward throttle
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, quadplane.forward_throttle_pct());
|
2016-10-09 05:14:17 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-10-09 05:21:12 -03:00
|
|
|
/*
|
|
|
|
setup flap outputs
|
|
|
|
*/
|
|
|
|
void Plane::set_servos_flaps(void)
|
2016-10-09 04:58:31 -03:00
|
|
|
{
|
|
|
|
// Auto flap deployment
|
|
|
|
int8_t auto_flap_percent = 0;
|
|
|
|
int8_t manual_flap_percent = 0;
|
|
|
|
|
|
|
|
// work out any manual flap input
|
2016-10-22 07:27:57 -03:00
|
|
|
RC_Channel *flapin = RC_Channels::rc_channel(g.flapin_channel-1);
|
2016-10-28 19:10:03 -03:00
|
|
|
if (flapin != nullptr && !failsafe.ch3_failsafe && failsafe.ch3_counter == 0) {
|
2016-10-09 04:58:31 -03:00
|
|
|
flapin->input();
|
|
|
|
manual_flap_percent = flapin->percent_input();
|
|
|
|
}
|
|
|
|
|
|
|
|
if (auto_throttle_mode) {
|
|
|
|
int16_t flapSpeedSource = 0;
|
|
|
|
if (ahrs.airspeed_sensor_enabled()) {
|
|
|
|
flapSpeedSource = target_airspeed_cm * 0.01f;
|
|
|
|
} else {
|
|
|
|
flapSpeedSource = aparm.throttle_cruise;
|
|
|
|
}
|
|
|
|
if (g.flap_2_speed != 0 && flapSpeedSource <= g.flap_2_speed) {
|
|
|
|
auto_flap_percent = g.flap_2_percent;
|
|
|
|
} else if ( g.flap_1_speed != 0 && flapSpeedSource <= g.flap_1_speed) {
|
|
|
|
auto_flap_percent = g.flap_1_percent;
|
|
|
|
} //else flaps stay at default zero deflection
|
|
|
|
|
2017-01-11 01:29:03 -04:00
|
|
|
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND && landing.get_flap_percent() != 0) {
|
2017-01-10 03:42:57 -04:00
|
|
|
auto_flap_percent = landing.get_flap_percent();
|
|
|
|
}
|
|
|
|
|
2016-10-09 04:58:31 -03:00
|
|
|
/*
|
|
|
|
special flap levels for takeoff and landing. This works
|
|
|
|
better than speed based flaps as it leads to less
|
|
|
|
possibility of oscillation
|
|
|
|
*/
|
|
|
|
if (control_mode == AUTO) {
|
|
|
|
switch (flight_stage) {
|
2016-12-13 22:20:57 -04:00
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF:
|
2016-12-13 23:18:48 -04:00
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND:
|
2016-10-09 04:58:31 -03:00
|
|
|
if (g.takeoff_flap_percent != 0) {
|
|
|
|
auto_flap_percent = g.takeoff_flap_percent;
|
|
|
|
}
|
|
|
|
break;
|
2016-12-13 22:20:57 -04:00
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_NORMAL:
|
2016-10-09 04:58:31 -03:00
|
|
|
if (auto_flap_percent != 0 && in_preLaunch_flight_stage()) {
|
|
|
|
// TODO: move this to a new FLIGHT_PRE_TAKEOFF stage
|
|
|
|
auto_flap_percent = g.takeoff_flap_percent;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// manual flap input overrides auto flap input
|
|
|
|
if (abs(manual_flap_percent) > auto_flap_percent) {
|
|
|
|
auto_flap_percent = manual_flap_percent;
|
|
|
|
}
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_flap_auto, auto_flap_percent);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_flap, manual_flap_percent);
|
2016-10-09 04:58:31 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
if (g.flap_slewrate) {
|
2017-01-07 02:14:08 -04:00
|
|
|
SRV_Channels::limit_slew_rate(SRV_Channel::k_flap_auto, g.flap_slewrate, G_Dt);
|
|
|
|
SRV_Channels::limit_slew_rate(SRV_Channel::k_flap, g.flap_slewrate, G_Dt);
|
2016-10-22 07:27:57 -03:00
|
|
|
}
|
2016-10-09 04:58:31 -03:00
|
|
|
|
2016-10-09 05:21:12 -03:00
|
|
|
if (g.flaperon_output != MIXING_DISABLED && g.elevon_output == MIXING_DISABLED && g.mix_mode == 0) {
|
|
|
|
flaperon_update(auto_flap_percent);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-10-12 01:50:46 -03:00
|
|
|
/*
|
|
|
|
apply vtail and elevon mixers
|
|
|
|
the rewrites radio_out for the corresponding channels
|
|
|
|
*/
|
|
|
|
void Plane::servo_output_mixers(void)
|
|
|
|
{
|
|
|
|
if (g.vtail_output != MIXING_DISABLED) {
|
2016-10-22 07:27:57 -03:00
|
|
|
channel_output_mixer(g.vtail_output, SRV_Channel::k_elevator, SRV_Channel::k_rudder);
|
2016-10-12 01:50:46 -03:00
|
|
|
} else if (g.elevon_output != MIXING_DISABLED) {
|
2016-10-22 07:27:57 -03:00
|
|
|
channel_output_mixer(g.elevon_output, SRV_Channel::k_elevator, SRV_Channel::k_aileron);
|
2016-10-12 01:50:46 -03:00
|
|
|
// if (both) differential spoilers setup then apply rudder
|
|
|
|
// control into splitting the two elevons on the side of
|
|
|
|
// the aircraft where we want to induce additional drag:
|
2016-10-22 07:27:57 -03:00
|
|
|
uint16_t ch3, ch4;
|
|
|
|
|
|
|
|
if (SRV_Channels::function_assigned(SRV_Channel::k_dspoiler1) &&
|
|
|
|
SRV_Channels::function_assigned(SRV_Channel::k_dspoiler2) &&
|
|
|
|
SRV_Channels::get_output_pwm(SRV_Channel::k_aileron, ch3) &&
|
|
|
|
SRV_Channels::get_output_pwm(SRV_Channel::k_elevator, ch4)) {
|
2016-10-12 01:50:46 -03:00
|
|
|
// convert rudder-servo output (-4500 to 4500) to PWM offset
|
|
|
|
// value (-500 to 500) and multiply by DSPOILR_RUD_RATE/100
|
|
|
|
// (rudder->servo_out * 500 / SERVO_MAX * dspoiler_rud_rate/100):
|
2016-10-22 07:27:57 -03:00
|
|
|
int16_t ruddVal = (int16_t)(int32_t(SRV_Channels::get_output_scaled(SRV_Channel::k_rudder)) *
|
2016-10-12 01:50:46 -03:00
|
|
|
g.dspoiler_rud_rate / (SERVO_MAX/5));
|
|
|
|
if (ruddVal != 0) { //if nonzero rudder then apply to spoilers
|
|
|
|
int16_t ch1 = ch3; //elevon 1
|
|
|
|
int16_t ch2 = ch4; //elevon 2
|
|
|
|
if (ruddVal > 0) { //apply rudder to right or left side
|
|
|
|
ch1 += ruddVal;
|
|
|
|
ch3 -= ruddVal;
|
|
|
|
} else {
|
|
|
|
ch2 += ruddVal;
|
|
|
|
ch4 -= ruddVal;
|
|
|
|
}
|
|
|
|
// change elevon 1 & 2 positions; constrain min/max:
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_pwm_first(SRV_Channel::k_aileron, constrain_int16(ch1, 900, 2100));
|
|
|
|
SRV_Channels::set_output_pwm_first(SRV_Channel::k_elevator, constrain_int16(ch2, 900, 2100));
|
2016-10-12 01:50:46 -03:00
|
|
|
// constrain min/max for intermediate dspoiler positions:
|
|
|
|
ch3 = constrain_int16(ch3, 900, 2100);
|
|
|
|
ch4 = constrain_int16(ch4, 900, 2100);
|
|
|
|
}
|
|
|
|
// set positions of differential spoilers (convert PWM
|
|
|
|
// 900-2100 range to servo output (-4500 to 4500)
|
|
|
|
// and use function that supports rev/min/max/trim):
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoiler1,
|
|
|
|
(int16_t(ch3)-1500) * (int16_t)(SERVO_MAX/300) / (int16_t)2);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoiler2,
|
|
|
|
(int16_t(ch4)-1500) * (int16_t)(SERVO_MAX/300) / (int16_t)2);
|
2016-10-12 01:50:46 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-02-12 21:03:22 -04:00
|
|
|
/*
|
|
|
|
support for twin-engine planes
|
|
|
|
*/
|
|
|
|
void Plane::servos_twin_engine_mix(void)
|
|
|
|
{
|
|
|
|
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
|
|
|
|
float rudder = SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) / float(SERVO_MAX);
|
|
|
|
float throttle_left, throttle_right;
|
|
|
|
|
|
|
|
if (throttle < 0 && aparm.throttle_min < 0) {
|
|
|
|
// doing reverse thrust
|
|
|
|
throttle_left = constrain_float(throttle + 50 * rudder, -100, 0);
|
|
|
|
throttle_right = constrain_float(throttle - 50 * rudder, -100, 0);
|
|
|
|
} else {
|
|
|
|
// doing forward thrust
|
|
|
|
throttle_left = constrain_float(throttle + 50 * rudder, 0, 100);
|
|
|
|
throttle_right = constrain_float(throttle - 50 * rudder, 0, 100);
|
|
|
|
}
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right);
|
|
|
|
}
|
|
|
|
|
2016-10-12 01:50:46 -03:00
|
|
|
|
2016-10-11 01:23:14 -03:00
|
|
|
/*
|
|
|
|
Set the flight control servos based on the current calculated values
|
|
|
|
|
|
|
|
This function operates by first building up output values for
|
|
|
|
channels using set_servo() and set_radio_out(). Using
|
|
|
|
set_radio_out() is for when a raw PWM value of output is given which
|
|
|
|
does not depend on any output scaling. Using set_servo() is for when
|
|
|
|
scaling and mixing will be needed.
|
|
|
|
|
|
|
|
Finally servos_output() is called to push the final PWM values
|
|
|
|
for output channels
|
|
|
|
*/
|
2016-10-09 05:21:12 -03:00
|
|
|
void Plane::set_servos(void)
|
|
|
|
{
|
2016-10-11 19:29:37 -03:00
|
|
|
// start with output corked. the cork is released when we run
|
|
|
|
// servos_output(), which is run from all code paths in this
|
|
|
|
// function
|
|
|
|
hal.rcout->cork();
|
|
|
|
|
2016-10-09 05:21:12 -03:00
|
|
|
// this is to allow the failsafe module to deliberately crash
|
|
|
|
// the plane. Only used in extreme circumstances to meet the
|
|
|
|
// OBC rules
|
|
|
|
if (afs.should_crash_vehicle()) {
|
|
|
|
afs.terminate_vehicle();
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// do any transition updates for quadplane
|
|
|
|
quadplane.update();
|
|
|
|
|
|
|
|
if (control_mode == AUTO && auto_state.idle_mode) {
|
|
|
|
// special handling for balloon launch
|
|
|
|
set_servos_idle();
|
2016-10-11 01:23:14 -03:00
|
|
|
servos_output();
|
2016-10-09 05:21:12 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
see if we are doing ground steering.
|
|
|
|
*/
|
|
|
|
if (!steering_control.ground_steering) {
|
|
|
|
// we are not at an altitude for ground steering. Set the nose
|
|
|
|
// wheel to the rudder just in case the barometer has drifted
|
|
|
|
// a lot
|
|
|
|
steering_control.steering = steering_control.rudder;
|
2016-10-22 07:27:57 -03:00
|
|
|
} else if (!SRV_Channels::function_assigned(SRV_Channel::k_steering)) {
|
2016-10-09 05:21:12 -03:00
|
|
|
// we are within the ground steering altitude but don't have a
|
|
|
|
// dedicated steering channel. Set the rudder to the ground
|
|
|
|
// steering output
|
|
|
|
steering_control.rudder = steering_control.steering;
|
|
|
|
}
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_control.rudder);
|
2016-10-09 05:21:12 -03:00
|
|
|
|
|
|
|
// clear ground_steering to ensure manual control if the yaw stabilizer doesn't run
|
|
|
|
steering_control.ground_steering = false;
|
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
if (control_mode == TRAINING) {
|
|
|
|
steering_control.rudder = channel_rudder->get_control_in();
|
|
|
|
}
|
|
|
|
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_control.rudder);
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_control.steering);
|
2016-10-09 05:21:12 -03:00
|
|
|
|
|
|
|
if (control_mode == MANUAL) {
|
|
|
|
set_servos_manual_passthrough();
|
|
|
|
} else {
|
|
|
|
set_servos_controlled();
|
|
|
|
}
|
|
|
|
|
|
|
|
// setup flap outputs
|
|
|
|
set_servos_flaps();
|
|
|
|
|
2016-10-09 04:58:31 -03:00
|
|
|
if (control_mode >= FLY_BY_WIRE_B ||
|
|
|
|
quadplane.in_assisted_flight() ||
|
|
|
|
quadplane.in_vtol_mode()) {
|
|
|
|
/* only do throttle slew limiting in modes where throttle
|
|
|
|
* control is automatic */
|
2016-10-22 07:27:57 -03:00
|
|
|
throttle_slew_limit();
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (!arming.is_armed()) {
|
|
|
|
//Some ESCs get noisy (beep error msgs) if PWM == 0.
|
|
|
|
//This little segment aims to avoid this.
|
|
|
|
switch (arming.arming_required()) {
|
|
|
|
case AP_Arming::NO:
|
|
|
|
//keep existing behavior: do nothing to radio_out
|
|
|
|
//(don't disarm throttle channel even if AP_Arming class is)
|
|
|
|
break;
|
|
|
|
|
|
|
|
case AP_Arming::YES_ZERO_PWM:
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_throttle, 0);
|
2016-10-09 04:58:31 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case AP_Arming::YES_MIN_PWM:
|
|
|
|
default:
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0);
|
2016-10-09 04:58:31 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
#if HIL_SUPPORT
|
|
|
|
if (g.hil_mode == 1) {
|
|
|
|
// get the servos to the GCS immediately for HIL
|
|
|
|
if (HAVE_PAYLOAD_SPACE(MAVLINK_COMM_0, RC_CHANNELS_SCALED)) {
|
|
|
|
send_servo_out(MAVLINK_COMM_0);
|
|
|
|
}
|
|
|
|
if (!g.hil_servos) {
|
2016-10-11 01:23:14 -03:00
|
|
|
// we don't run the output mixer
|
2016-10-09 04:58:31 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2016-11-23 06:18:21 -04:00
|
|
|
if (landing.get_then_servos_neutral() > 0 &&
|
2016-10-09 04:58:31 -03:00
|
|
|
control_mode == AUTO &&
|
2016-11-23 06:18:21 -04:00
|
|
|
landing.get_disarm_delay() > 0 &&
|
2016-12-12 04:47:52 -04:00
|
|
|
landing.is_complete() &&
|
2016-10-09 04:58:31 -03:00
|
|
|
!arming.is_armed()) {
|
|
|
|
// after an auto land and auto disarm, set the servos to be neutral just
|
|
|
|
// in case we're upside down or some crazy angle and straining the servos.
|
2016-11-23 06:18:21 -04:00
|
|
|
if (landing.get_then_servos_neutral() == 1) {
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_aileron, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_elevator, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_rudder, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
2016-11-23 06:18:21 -04:00
|
|
|
} else if (landing.get_then_servos_neutral() == 2) {
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_aileron, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_elevator, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_rudder, SRV_Channel::SRV_CHANNEL_LIMIT_ZERO_PWM);
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t override_pct;
|
|
|
|
if (g2.ice_control.throttle_override(override_pct)) {
|
|
|
|
// the ICE controller wants to override the throttle for starting
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, override_pct);
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|
|
|
|
|
2017-02-12 21:03:22 -04:00
|
|
|
// support twin-engine aircraft
|
|
|
|
servos_twin_engine_mix();
|
|
|
|
|
2016-10-11 01:23:14 -03:00
|
|
|
// run output mixer and send values to the hal for output
|
|
|
|
servos_output();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
run configured output mixer. This takes calculated servo_out values
|
|
|
|
for each channel and calculates PWM values, then pushes them to
|
|
|
|
hal.rcout
|
|
|
|
*/
|
|
|
|
void Plane::servos_output(void)
|
|
|
|
{
|
2016-10-11 08:02:20 -03:00
|
|
|
hal.rcout->cork();
|
2016-10-12 01:50:46 -03:00
|
|
|
|
2017-02-11 01:50:03 -04:00
|
|
|
// cope with tailsitters
|
|
|
|
quadplane.tailsitter_output();
|
|
|
|
|
2017-01-07 18:29:12 -04:00
|
|
|
// the mixers need pwm to be calculated now
|
|
|
|
SRV_Channels::calc_pwm();
|
|
|
|
|
2016-10-12 01:50:46 -03:00
|
|
|
// run vtail and elevon mixers
|
|
|
|
servo_output_mixers();
|
2016-10-11 01:23:14 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::calc_pwm();
|
|
|
|
|
|
|
|
SRV_Channels::output_ch_all();
|
2016-10-11 08:02:20 -03:00
|
|
|
|
|
|
|
hal.rcout->push();
|
2016-10-15 07:40:26 -03:00
|
|
|
|
2016-10-15 07:41:55 -03:00
|
|
|
if (g2.servo_channels.auto_trim_enabled()) {
|
|
|
|
servos_auto_trim();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
implement automatic persistent trim of control surfaces with
|
|
|
|
AUTO_TRIM=2, only available when SERVO_RNG_ENABLE=1 as otherwise it
|
|
|
|
would impact R/C transmitter calibration
|
|
|
|
*/
|
|
|
|
void Plane::servos_auto_trim(void)
|
|
|
|
{
|
|
|
|
// only in auto modes and FBWA
|
|
|
|
if (!auto_throttle_mode && control_mode != FLY_BY_WIRE_A) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (!hal.util->get_soft_armed()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (!is_flying()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (quadplane.in_assisted_flight() || quadplane.in_vtol_mode()) {
|
|
|
|
// can't auto-trim with quadplane motors running
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (abs(nav_roll_cd) > 700 || abs(nav_pitch_cd) > 700) {
|
|
|
|
// only when close to level
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if (now - auto_trim.last_trim_check < 500) {
|
|
|
|
// check twice a second. We want slow trim update
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (ahrs.groundspeed() < 8 || smoothed_airspeed < 8) {
|
2016-10-20 10:18:18 -03:00
|
|
|
// only when definitely moving
|
2016-10-15 07:41:55 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// adjust trim on channels by a small amount according to I value
|
2016-10-22 07:27:57 -03:00
|
|
|
g2.servo_channels.adjust_trim(SRV_Channel::k_aileron, rollController.get_pid_info().I);
|
|
|
|
g2.servo_channels.adjust_trim(SRV_Channel::k_elevator, pitchController.get_pid_info().I);
|
2016-10-15 07:41:55 -03:00
|
|
|
|
|
|
|
auto_trim.last_trim_check = now;
|
|
|
|
|
|
|
|
if (now - auto_trim.last_trim_save > 10000) {
|
|
|
|
auto_trim.last_trim_save = now;
|
|
|
|
g2.servo_channels.save_trim();
|
|
|
|
}
|
|
|
|
|
2016-10-09 04:58:31 -03:00
|
|
|
}
|