RC_Channel: added secondary rudder support

this is used when nose wheel steering needs different reverse/range
from rudder
This commit is contained in:
Andrew Tridgell 2013-06-29 10:14:43 +10:00
parent b16ce5e523
commit 6b7b69a048
2 changed files with 3 additions and 7 deletions

View File

@ -12,7 +12,7 @@ const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = {
// @Param: FUNCTION // @Param: FUNCTION
// @DisplayName: Servo out function // @DisplayName: Servo out function
// @Description: Setting this to Disabled(0) will disable this output, any other value will enable the corresponding function // @Description: Setting this to Disabled(0) will disable this output, any other value will enable the corresponding function
// @Values: 0:Disabled,1:Manual,2:Flap,3:Flap_auto,4:Aileron,5:flaperon,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoiler1,17:DifferentialSpoiler2,18:AileronWithInput,19:Elevator,20:ElevatorWithInput // @Values: 0:Disabled,1:Manual,2:Flap,3:Flap_auto,4:Aileron,5:flaperon,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoiler1,17:DifferentialSpoiler2,18:AileronWithInput,19:Elevator,20:ElevatorWithInput,21:Rudder
// @User: Standard // @User: Standard
AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function, 0), AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function, 0),
@ -75,16 +75,11 @@ void update_aux_servo_function( RC_Channel_aux* rc_a,
break; break;
case RC_Channel_aux::k_aileron: case RC_Channel_aux::k_aileron:
case RC_Channel_aux::k_aileron_with_input: case RC_Channel_aux::k_aileron_with_input:
_aux_channels[i]->set_angle(4500);
break;
case RC_Channel_aux::k_elevator: case RC_Channel_aux::k_elevator:
case RC_Channel_aux::k_elevator_with_input: case RC_Channel_aux::k_elevator_with_input:
_aux_channels[i]->set_angle(4500);
break;
case RC_Channel_aux::k_dspoiler1: case RC_Channel_aux::k_dspoiler1:
_aux_channels[i]->set_angle(4500);
break;
case RC_Channel_aux::k_dspoiler2: case RC_Channel_aux::k_dspoiler2:
case RC_Channel_aux::k_rudder:
_aux_channels[i]->set_angle(4500); _aux_channels[i]->set_angle(4500);
break; break;
default: default:

View File

@ -47,6 +47,7 @@ public:
k_aileron_with_input = 18, ///< aileron, with rc input k_aileron_with_input = 18, ///< aileron, with rc input
k_elevator = 19, ///< elevator k_elevator = 19, ///< elevator
k_elevator_with_input = 20, ///< elevator, with rc input k_elevator_with_input = 20, ///< elevator, with rc input
k_rudder = 21, ///< secondary rudder channel
k_nr_aux_servo_functions ///< This must be the last enum value (only add new values _before_ this one) k_nr_aux_servo_functions ///< This must be the last enum value (only add new values _before_ this one)
} Aux_servo_function_t; } Aux_servo_function_t;