mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Plane: add crow flap options paramiter
This commit is contained in:
parent
c484b93314
commit
520f5f7894
@ -1189,20 +1189,22 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
#endif
|
||||
|
||||
// @Param: DSPOILER_CROW_W1
|
||||
// @DisplayName: Differential spoiler crow flaps inner weight
|
||||
// @Description: This is amount of deflection applied to the two inner surfaces for differential spoilers for flaps to give crow flaps. It is a number from 0 to 100. At zero no crow flaps are applied. A recommended starting value is 25.
|
||||
// @DisplayName: Differential spoiler crow flaps outer weight
|
||||
// @Description: This is amount of deflection applied to the two outer surfaces for differential spoilers for flaps to give crow flaps. It is a number from 0 to 100. At zero no crow flaps are applied. A recommended starting value is 25.
|
||||
// @Range: 0 100
|
||||
// @Units: %
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DSPOILER_CROW_W1", 17, ParametersG2, crow_flap_weight1, 0),
|
||||
AP_GROUPINFO("DSPOILER_CROW_W1", 17, ParametersG2, crow_flap_weight_outer, 0),
|
||||
|
||||
// @Param: DSPOILER_CROW_W2
|
||||
// @DisplayName: Differential spoiler crow flaps outer weight
|
||||
// @Description: This is amount of deflection applied to the two outer surfaces for differential spoilers for flaps to give crow flaps. It is a number from 0 to 100. At zero no crow flaps are applied. A recommended starting value is 45.
|
||||
// @DisplayName: Differential spoiler crow flaps inner weight
|
||||
// @Description: This is amount of deflection applied to the two inner surfaces for differential spoilers for flaps to give crow flaps. It is a number from 0 to 100. At zero no crow flaps are applied. A recommended starting value is 45.
|
||||
// @Range: 0 100
|
||||
// @Units: %
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DSPOILER_CROW_W2", 18, ParametersG2, crow_flap_weight2, 0),
|
||||
AP_GROUPINFO("DSPOILER_CROW_W2", 18, ParametersG2, crow_flap_weight_inner, 0),
|
||||
|
||||
// @Param: TKOFF_TIMEOUT
|
||||
// @DisplayName: Takeoff timeout
|
||||
@ -1212,7 +1214,24 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @Units: s
|
||||
// @User: User
|
||||
AP_GROUPINFO("TKOFF_TIMEOUT", 19, ParametersG2, takeoff_timeout, 0),
|
||||
|
||||
|
||||
// @Param: DSPOILER_OPTS
|
||||
// @DisplayName: Differential spoiler and crow flaps options
|
||||
// @Description: Differential spoiler and crow flaps options
|
||||
// @Values: 0: none, 1: D spoilers have pitch input, 2: use both control surfaces on each wing for roll, 4: Progressive crow, flaps only first (0-50% flap in) then crow flaps (50 - 100% flap in)
|
||||
// @Bitmask: 0:pitch control, 1:full span, 2:Progressive crow
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DSPOILER_OPTS", 20, ParametersG2, crow_flap_options, 3),
|
||||
|
||||
// @Param: DSPOILER_AILMTCH
|
||||
// @DisplayName: Differential spoiler aileron matching
|
||||
// @Description: This scales down the inner flaps so less than full downwards range can be used for differential spoiler and full span ailerons, 100 is use full range, upwards travel is unaffected
|
||||
// @Range: 0 100
|
||||
// @Units: %
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DSPOILER_AILMTCH", 21, ParametersG2, crow_flap_aileron_matching, 100),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -557,8 +557,10 @@ public:
|
||||
#endif
|
||||
|
||||
// crow flaps weighting
|
||||
AP_Int8 crow_flap_weight1;
|
||||
AP_Int8 crow_flap_weight2;
|
||||
AP_Int8 crow_flap_weight_outer;
|
||||
AP_Int8 crow_flap_weight_inner;
|
||||
AP_Int8 crow_flap_options;
|
||||
AP_Int8 crow_flap_aileron_matching;
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
@ -182,3 +182,10 @@ enum FlightOptions {
|
||||
DISABLE_TOFF_ATTITUDE_CHK = (1 << 2),
|
||||
CRUISE_TRIM_AIRSPEED = (1 << 3),
|
||||
};
|
||||
|
||||
enum CrowFlapOptions {
|
||||
FLYINGWING = (1 << 0),
|
||||
FULLSPAN = (1 << 1),
|
||||
PROGRESSIVE_CROW = (1 << 2),
|
||||
};
|
||||
|
||||
|
@ -197,51 +197,91 @@ void Plane::dspoiler_update(void)
|
||||
if (!SRV_Channels::function_assigned(SRV_Channel::k_dspoilerLeft1)) {
|
||||
return;
|
||||
}
|
||||
float elevon_left = SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_left);
|
||||
float elevon_right = SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_right);
|
||||
float rudder_rate = g.dspoiler_rud_rate * 0.01f;
|
||||
float rudder = SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) * rudder_rate;
|
||||
float dspoiler1_left = elevon_left;
|
||||
float dspoiler2_left = elevon_left;
|
||||
float dspoiler1_right = elevon_right;
|
||||
float dspoiler2_right = elevon_right;
|
||||
|
||||
const int8_t bitmask = g2.crow_flap_options.get();
|
||||
const bool flying_wing = bitmask & CrowFlapOptions::FLYINGWING;
|
||||
const bool full_span_aileron = bitmask & CrowFlapOptions::FULLSPAN;
|
||||
const bool progresive_crow = bitmask & CrowFlapOptions::PROGRESSIVE_CROW;
|
||||
|
||||
// if flying wing use elevons else use ailerons
|
||||
float elevon_left;
|
||||
float elevon_right;
|
||||
if (flying_wing) {
|
||||
elevon_left = SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_left);
|
||||
elevon_right = SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_right);
|
||||
} else {
|
||||
const float aileron = SRV_Channels::get_output_scaled(SRV_Channel::k_aileron);
|
||||
elevon_left = -aileron;
|
||||
elevon_right = aileron;
|
||||
}
|
||||
|
||||
const float rudder_rate = g.dspoiler_rud_rate * 0.01f;
|
||||
const float rudder = SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) * rudder_rate;
|
||||
float dspoiler_outer_left = elevon_left;
|
||||
float dspoiler_outer_right = elevon_right;
|
||||
|
||||
float dspoiler_inner_left = 0;
|
||||
float dspoiler_inner_right = 0;
|
||||
|
||||
// full span ailerons / elevons
|
||||
if (full_span_aileron) {
|
||||
dspoiler_inner_left = elevon_left;
|
||||
dspoiler_inner_right = elevon_right;
|
||||
}
|
||||
|
||||
if (rudder > 0) {
|
||||
// apply rudder to right wing
|
||||
dspoiler1_right = constrain_float(elevon_right + rudder, -4500, 4500);
|
||||
dspoiler2_right = constrain_float(elevon_right - rudder, -4500, 4500);
|
||||
dspoiler_outer_right = constrain_float(dspoiler_outer_right + rudder, -4500, 4500);
|
||||
dspoiler_inner_right = constrain_float(dspoiler_inner_right - rudder, -4500, 4500);
|
||||
} else {
|
||||
// apply rudder to left wing
|
||||
dspoiler1_left = constrain_float(elevon_left - rudder, -4500, 4500);
|
||||
dspoiler2_left = constrain_float(elevon_left + rudder, -4500, 4500);
|
||||
dspoiler_outer_left = constrain_float(dspoiler_outer_left - rudder, -4500, 4500);
|
||||
dspoiler_inner_left = constrain_float(dspoiler_inner_left + rudder, -4500, 4500);
|
||||
}
|
||||
|
||||
const int16_t weight1 = g2.crow_flap_weight1.get();
|
||||
const int16_t weight2 = g2.crow_flap_weight2.get();
|
||||
if (weight1 > 0 || weight2 > 0) {
|
||||
// limit flap throw used for aileron
|
||||
const int8_t aileron_matching = g2.crow_flap_aileron_matching.get();
|
||||
if (aileron_matching < 100) {
|
||||
// only do matching if it will make a difference
|
||||
const float aileron_matching_scaled = aileron_matching * 0.01;
|
||||
if (is_negative(dspoiler_inner_left)) {
|
||||
dspoiler_inner_left *= aileron_matching_scaled;
|
||||
}
|
||||
if (is_negative(dspoiler_inner_right)) {
|
||||
dspoiler_inner_right *= aileron_matching_scaled;
|
||||
}
|
||||
}
|
||||
|
||||
const int16_t weight_outer = g2.crow_flap_weight_outer.get();
|
||||
const int16_t weight_inner = g2.crow_flap_weight_inner.get();
|
||||
if (weight_outer > 0 || weight_inner > 0) {
|
||||
/*
|
||||
apply crow flaps by apply the same split of the differential
|
||||
spoilers to both wings. Get flap percentage from k_flap_auto, which is set
|
||||
in set_servos_flaps() as the maximum of manual and auto flap control
|
||||
*/
|
||||
int16_t flap_percent = SRV_Channels::get_output_scaled(SRV_Channel::k_flap_auto);
|
||||
|
||||
// scale flaps so when weights are 100 they give full up or down
|
||||
const float flap_scaled = ((float)flap_percent) * 0.45;
|
||||
const int16_t flap_percent = SRV_Channels::get_output_scaled(SRV_Channel::k_flap_auto);
|
||||
|
||||
if (flap_percent > 0) {
|
||||
//apply crow brakes to both wings using flap percentage
|
||||
dspoiler1_left = constrain_float(dspoiler1_left + flap_scaled * weight1, -4500, 4500);
|
||||
dspoiler2_left = constrain_float(dspoiler2_left - flap_scaled * weight2, -4500, 4500);
|
||||
dspoiler1_right = constrain_float(dspoiler1_right + flap_scaled * weight1, -4500, 4500);
|
||||
dspoiler2_right = constrain_float(dspoiler2_right - flap_scaled * weight2, -4500, 4500);
|
||||
float inner_flap_scaled = (float)flap_percent;
|
||||
float outer_flap_scaled = (float)flap_percent;
|
||||
if (progresive_crow) {
|
||||
// apply 0 - full inner from 0 to 50% flap then add in outer above 50%
|
||||
inner_flap_scaled = constrain_float(inner_flap_scaled * 2, 0,100);
|
||||
outer_flap_scaled = constrain_float(outer_flap_scaled - 50, 0,50) * 2;
|
||||
}
|
||||
// scale flaps so when weights are 100 they give full up or down
|
||||
dspoiler_outer_left = constrain_float(dspoiler_outer_left + outer_flap_scaled * weight_outer * 0.45, -4500, 4500);
|
||||
dspoiler_inner_left = constrain_float(dspoiler_inner_left - inner_flap_scaled * weight_inner * 0.45, -4500, 4500);
|
||||
dspoiler_outer_right = constrain_float(dspoiler_outer_right + outer_flap_scaled * weight_outer * 0.45, -4500, 4500);
|
||||
dspoiler_inner_right = constrain_float(dspoiler_inner_right - inner_flap_scaled * weight_inner * 0.45, -4500, 4500);
|
||||
}
|
||||
}
|
||||
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoilerLeft1, dspoiler1_left);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoilerLeft2, dspoiler2_left);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoilerRight1, dspoiler1_right);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoilerRight2, dspoiler2_right);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoilerLeft1, dspoiler_outer_left);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoilerLeft2, dspoiler_inner_left);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoilerRight1, dspoiler_outer_right);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_dspoilerRight2, dspoiler_inner_right);
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user