11 #define AP_MOTORS_CH_TRI_YAW CH_7 13 #define AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN 5 // minimum angle movement of tail servo in degrees 14 #define AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX 80 // maximum angle movement of tail servo in degrees
virtual void output_test(uint8_t motor_seq, int16_t pwm)
AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Constructor.
void output_armed_stabilizing()
#define AP_MOTORS_SPEED_DEFAULT
void thrust_compensation(void) override
int16_t calc_yaw_radio_output(float yaw_input, float yaw_input_max)
void init(motor_frame_class frame_class, motor_frame_type frame_type)
Common definitions and utility routines for the ArduPilot libraries.
virtual uint16_t get_motor_mask()
Motor control class for Multicopters.
void output_motor_mask(float thrust, uint8_t mask) override
virtual void output_to_motors()
void set_update_rate(uint16_t speed_hz)
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)