mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: added support for separate wheel steering channels on planes
This commit is contained in:
parent
8d95b953c3
commit
dd502e98b4
|
@ -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 setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
|
// @Description: Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
|
||||||
// @Values: 0:Disabled,1:RCPassThru,2:Flap,3:Flap_auto,4:Aileron,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,24:Flaperon1,25:Flaperon2
|
// @Values: 0:Disabled,1:RCPassThru,2:Flap,3:Flap_auto,4:Aileron,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,24:Flaperon1,25:Flaperon2,26:GroundSteering
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function, 0),
|
AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function, 0),
|
||||||
|
|
||||||
|
@ -80,6 +80,7 @@ void RC_Channel_aux::update_aux_servo_function(void)
|
||||||
case RC_Channel_aux::k_dspoiler1:
|
case RC_Channel_aux::k_dspoiler1:
|
||||||
case RC_Channel_aux::k_dspoiler2:
|
case RC_Channel_aux::k_dspoiler2:
|
||||||
case RC_Channel_aux::k_rudder:
|
case RC_Channel_aux::k_rudder:
|
||||||
|
case RC_Channel_aux::k_steering:
|
||||||
_aux_channels[i]->set_angle(4500);
|
_aux_channels[i]->set_angle(4500);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
|
|
@ -60,6 +60,7 @@ public:
|
||||||
k_sprayer_spinner = 23, ///< crop sprayer spinner channel
|
k_sprayer_spinner = 23, ///< crop sprayer spinner channel
|
||||||
k_flaperon1 = 24, ///< flaperon, left wing
|
k_flaperon1 = 24, ///< flaperon, left wing
|
||||||
k_flaperon2 = 25, ///< flaperon, right wing
|
k_flaperon2 = 25, ///< flaperon, right wing
|
||||||
|
k_steering = 26, ///< ground steering, used to separate from rudder
|
||||||
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;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue