10 #define AP_MOTORS_MATRIX_YAW_FACTOR_CW -1 11 #define AP_MOTORS_MATRIX_YAW_FACTOR_CCW 1 49 void add_motor_raw(int8_t motor_num,
float roll_fac,
float pitch_fac,
float yaw_fac, uint8_t testing_order);
52 void add_motor(int8_t motor_num,
float angle_degrees,
float yaw_factor, uint8_t testing_order);
55 void add_motor(int8_t motor_num,
float roll_factor_in_degrees,
float pitch_factor_in_degrees,
float yaw_factor, uint8_t testing_order);
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]
void remove_motor(int8_t motor_num)
motor_frame_type _last_frame_type
motor_frame_class _last_frame_class
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]
virtual void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type)
void normalise_rpy_factors()
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order)
void thrust_compensation(void) override
#define AP_MOTORS_SPEED_DEFAULT
uint8_t _test_order[AP_MOTORS_MAX_NUM_MOTORS]
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
void output_armed_stabilizing()
void output_test(uint8_t motor_seq, int16_t pwm)
RC_Channel manager, with EEPROM-backed storage of constants.
void init(motor_frame_class frame_class, motor_frame_type frame_type)
uint16_t get_motor_mask()
void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order)
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]
Common definitions and utility routines for the ArduPilot libraries.
float _thrust_rpyt_out[AP_MOTORS_MAX_NUM_MOTORS]
void set_update_rate(uint16_t speed_hz)
AP_MotorsMatrix(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Constructor.
Motor control class for Multicopters.
#define AP_MOTORS_MAX_NUM_MOTORS