11 #define AP_MOTORS_COAX_POSITIVE 1 12 #define AP_MOTORS_COAX_NEGATIVE -1 14 #define NUM_ACTUATORS 4 16 #define AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS 250 // update rate for digital servos 17 #define AP_MOTORS_SINGLE_SPEED_ANALOG_SERVOS 125 // update rate for analog servos 19 #define AP_MOTORS_COAX_SERVO_INPUT_RANGE 4500 // roll or pitch input of -4500 will cause servos to their minimum (i.e. radio_min), +4500 will move them to their maximum (i.e. radio_max) virtual void output_test(uint8_t motor_seq, int16_t pwm)
void set_update_rate(uint16_t speed_hz)
#define AP_MOTORS_SPEED_DEFAULT
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
virtual void output_to_motors()
virtual uint16_t get_motor_mask()
AP_MotorsCoax(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Constructor.
Common definitions and utility routines for the ArduPilot libraries.
void output_armed_stabilizing()
Motor control class for Multicopters.
void init(motor_frame_class frame_class, motor_frame_type frame_type)
float _actuator_out[NUM_ACTUATORS]