mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: added left and right motor tilt controls
This commit is contained in:
parent
01de4b1176
commit
37301f67a0
@ -103,6 +103,8 @@ public:
|
||||
k_tracker_pitch = 72, ///< antennatracker pitch
|
||||
k_throttleLeft = 73,
|
||||
k_throttleRight = 74,
|
||||
k_tiltMotorLeft = 75, ///< vectored thrust, left tilt
|
||||
k_tiltMotorRight = 76, ///< vectored thrust, right tilt
|
||||
k_nr_aux_servo_functions ///< This must be the last enum value (only add new values _before_ this one)
|
||||
} Aux_servo_function_t;
|
||||
|
||||
|
@ -106,6 +106,8 @@ void SRV_Channel::aux_servo_function_setup(void)
|
||||
case k_steering:
|
||||
case k_flaperon1:
|
||||
case k_flaperon2:
|
||||
case k_tiltMotorLeft:
|
||||
case k_tiltMotorRight:
|
||||
set_angle(4500);
|
||||
break;
|
||||
case k_throttle:
|
||||
|
Loading…
Reference in New Issue
Block a user