@ -197,51 +197,91 @@ void Plane::dspoiler_update(void)
if ( ! SRV_Channels : : function_assigned ( SRV_Channel : : k_dspoilerLeft1 ) ) {
if ( ! SRV_Channels : : function_assigned ( SRV_Channel : : k_dspoilerLeft1 ) ) {
return ;
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 ) ;
const int8_t bitmask = g2 . crow_flap_options . get ( ) ;
float rudder_rate = g . dspoiler_rud_rate * 0.01f ;
const bool flying_wing = bitmask & CrowFlapOptions : : FLYINGWING ;
float rudder = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_rudder ) * rudder_rate ;
const bool full_span_aileron = bitmask & CrowFlapOptions : : FULLSPAN ;
float dspoiler1_left = elevon_left ;
const bool progresive_crow = bitmask & CrowFlapOptions : : PROGRESSIVE_CROW ;
float dspoiler2_left = elevon_left ;
float dspoiler1_right = elevon_right ;
// if flying wing use elevons else use ailerons
float dspoiler2_right = elevon_right ;
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 ) {
if ( rudder > 0 ) {
// apply rudder to right wing
// apply rudder to right wing
dspoiler1_right = constrain_float ( elevon_right + rudder , - 4500 , 4500 ) ;
dspoiler_outer _right = constrain_float ( dspoiler_outer _right + rudder , - 4500 , 4500 ) ;
dspoiler2_right = constrain_float ( elevon_right - rudder , - 4500 , 4500 ) ;
dspoiler_inner _right = constrain_float ( dspoiler_inner _right - rudder , - 4500 , 4500 ) ;
} else {
} else {
// apply rudder to left wing
// apply rudder to left wing
dspoiler1_left = constrain_float ( elevon_left - rudder , - 4500 , 4500 ) ;
dspoiler_outer _left = constrain_float ( dspoiler_outer _left - rudder , - 4500 , 4500 ) ;
dspoiler2_left = constrain_float ( elevon_left + rudder , - 4500 , 4500 ) ;
dspoiler_inner _left = constrain_float ( dspoiler_inner _left + rudder , - 4500 , 4500 ) ;
}
}
const int16_t weight1 = g2 . crow_flap_weight1 . get ( ) ;
// limit flap throw used for aileron
const int16_t weight2 = g2 . crow_flap_weight2 . get ( ) ;
const int8_t aileron_matching = g2 . crow_flap_aileron_matching . get ( ) ;
if ( weight1 > 0 | | weight2 > 0 ) {
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
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
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
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 ) ;
const 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 ) {
if ( flap_percent > 0 ) {
//apply crow brakes to both wings using flap percentage
float inner_flap_scaled = ( float ) flap_percent ;
dspoiler1_left = constrain_float ( dspoiler1_left + flap_scaled * weight1 , - 4500 , 4500 ) ;
float outer_flap_scaled = ( float ) flap_percent ;
dspoiler2_left = constrain_float ( dspoiler2_left - flap_scaled * weight2 , - 4500 , 4500 ) ;
if ( progresive_crow ) {
dspoiler1_right = constrain_float ( dspoiler1_right + flap_scaled * weight1 , - 4500 , 4500 ) ;
// apply 0 - full inner from 0 to 50% flap then add in outer above 50%
dspoiler2_right = constrain_float ( dspoiler2_right - flap_scaled * weight2 , - 4500 , 4500 ) ;
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_dspoilerLeft1 , dspoiler_outer _left ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_dspoilerLeft2 , dspoiler2_left ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_dspoilerLeft2 , dspoiler_inner _left ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_dspoilerRight1 , dspoiler1_right ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_dspoilerRight1 , dspoiler_outer _right ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_dspoilerRight2 , dspoiler2_right ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_dspoilerRight2 , dspoiler_inner _right ) ;
}
}
/*
/*