APM:Libraries
AP_MotorsMatrix.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Common/AP_Common.h>
6 #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
7 #include <RC_Channel/RC_Channel.h> // RC Channel Library
8 #include "AP_MotorsMulticopter.h"
9 
10 #define AP_MOTORS_MATRIX_YAW_FACTOR_CW -1
11 #define AP_MOTORS_MATRIX_YAW_FACTOR_CCW 1
12 
15 public:
16 
18  AP_MotorsMatrix(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
19  AP_MotorsMulticopter(loop_rate, speed_hz)
20  {};
21 
22  // init
23  void init(motor_frame_class frame_class, motor_frame_type frame_type);
24 
25  // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
26  void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type);
27 
28  // set update rate to motors - a value in hertz
29  // you must have setup_motors before calling this
30  void set_update_rate(uint16_t speed_hz);
31 
32  // output_test - spin a motor at the pwm value specified
33  // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
34  // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
35  void output_test(uint8_t motor_seq, int16_t pwm);
36 
37  // output_to_motors - sends minimum values out to the motors
38  void output_to_motors();
39 
40  // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
41  // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
42  uint16_t get_motor_mask();
43 
44 protected:
45  // output - sends commands to the motors
47 
48  // add_motor using raw roll, pitch, throttle and yaw factors
49  void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order);
50 
51  // add_motor using just position and yaw_factor (or prop direction)
52  void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order);
53 
54  // add_motor using separate roll and pitch factors (for asymmetrical frames) and prop direction
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);
56 
57  // remove_motor
58  void remove_motor(int8_t motor_num);
59 
60  // configures the motors for the defined frame_class and frame_type
61  virtual void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type);
62 
63  // normalizes the roll, pitch and yaw factors so maximum magnitude is 0.5
64  void normalise_rpy_factors();
65 
66  // call vehicle supplied thrust compensation if set
67  void thrust_compensation(void) override;
68 
69  float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to roll
70  float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to pitch
71  float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to yaw (normally 1 or -1)
72  float _thrust_rpyt_out[AP_MOTORS_MAX_NUM_MOTORS]; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range
73  uint8_t _test_order[AP_MOTORS_MAX_NUM_MOTORS]; // order of the motors in the test sequence
74  motor_frame_class _last_frame_class; // most recently requested frame class (i.e. quad, hexa, octa, etc)
75  motor_frame_type _last_frame_type; // most recently requested frame type (i.e. plus, x, v, etc)
76 };
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 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)
static uint16_t pwm
Definition: RCOutput.cpp:20
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