SRV_Channel: added direct output of rate control on multicopters

This commit is contained in:
Andrew Tridgell 2019-10-15 10:25:33 +11:00
parent 85f963b961
commit 892f2d4256
2 changed files with 8 additions and 0 deletions

View File

@ -147,6 +147,10 @@ public:
k_LED_neopixel2 = 121,
k_LED_neopixel3 = 122,
k_LED_neopixel4 = 123,
k_roll_out = 124,
k_pitch_out = 125,
k_thrust_out = 126,
k_yaw_out = 127,
k_nr_aux_servo_functions ///< This must be the last enum value (only add new values _before_ this one)
} Aux_servo_function_t;

View File

@ -104,6 +104,7 @@ void SRV_Channel::aux_servo_function_setup(void)
case k_heli_tail_rsc:
case k_motor_tilt:
case k_boost_throttle:
case k_thrust_out:
set_range(1000);
break;
case k_aileron_with_input:
@ -124,6 +125,9 @@ void SRV_Channel::aux_servo_function_setup(void)
case k_elevon_right:
case k_vtail_left:
case k_vtail_right:
case k_roll_out:
case k_pitch_out:
case k_yaw_out:
set_angle(4500);
break;
case k_throttle: