Browse Source

SRV_Channel: added direct output of rate control on multicopters

c415-sdk
Andrew Tridgell 5 years ago
parent
commit
892f2d4256
  1. 4
      libraries/SRV_Channel/SRV_Channel.h
  2. 4
      libraries/SRV_Channel/SRV_Channel_aux.cpp

4
libraries/SRV_Channel/SRV_Channel.h

@ -147,6 +147,10 @@ public:
k_LED_neopixel2 = 121, k_LED_neopixel2 = 121,
k_LED_neopixel3 = 122, k_LED_neopixel3 = 122,
k_LED_neopixel4 = 123, 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) 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;

4
libraries/SRV_Channel/SRV_Channel_aux.cpp

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

Loading…
Cancel
Save