Plane: added parameters for crow flaps

DSPOILER_CROW_W1 and DSPOILER_CROW_W2 for inner and outer control
surfaces
This commit is contained in:
Andrew Tridgell 2018-11-19 21:20:24 +11:00
parent 4d6547c533
commit 1d00d26b9e
3 changed files with 46 additions and 11 deletions

View File

@ -1195,6 +1195,22 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear),
#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.
// @Range: 0 100
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("DSPOILER_CROW_W1", 17, ParametersG2, crow_flap_weight1, 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.
// @Range: 0 100
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("DSPOILER_CROW_W2", 18, ParametersG2, crow_flap_weight2, 0),
AP_GROUPEND
};

View File

@ -555,6 +555,10 @@ public:
#if LANDING_GEAR_ENABLED == ENABLED
AP_LandingGear landing_gear;
#endif
// crow flaps weighting
AP_Int8 crow_flap_weight1;
AP_Int8 crow_flap_weight2;
};
extern const AP_Param::Info var_info[];

View File

@ -205,24 +205,39 @@ void Plane::dspoiler_update(void)
float dspoiler2_left = elevon_left;
float dspoiler1_right = elevon_right;
float dspoiler2_right = elevon_right;
RC_Channel *flapin = RC_Channels::rc_channel(g.flapin_channel-1);
int8_t flap_percent = flapin->percent_input();;
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);
} else {
// apply rudder to left wing
dspoiler1_left = constrain_float(elevon_left - rudder, -4500, 4500);
dspoiler2_left = constrain_float(elevon_left + rudder, -4500, 4500);
dspoiler1_left = constrain_float(elevon_left + rudder, -4500, 4500);
dspoiler2_left = constrain_float(elevon_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) {
/*
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;
if (flap_percent > 0) {
//apply crow brakes to both wings
dspoiler1_left = constrain_float(elevon_left + flap_percent * 25, -4500, 4500);
dspoiler2_left = constrain_float(elevon_left - flap_percent * 45, -4500, 4500);
dspoiler1_right = constrain_float(elevon_right + flap_percent * 25, -4500, 4500);
dspoiler2_right = constrain_float(elevon_right - flap_percent * 45, -4500, 4500);
//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);
}
}
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);