AP_Motors: remove motor_num from motor definition structures
Every structure simply used the defines in sequence, meaning 0, 1, 2, 3 etc. Handily we have a loop counter where we use these structures...
This commit is contained in:
parent
a152ad70a9
commit
dbb43a5746
@ -565,14 +565,14 @@ void AP_MotorsMatrix::add_motors(T *motors, uint8_t num_motors)
|
||||
{
|
||||
for (uint8_t i=0; i<num_motors; i++) {
|
||||
const auto &motor = motors[i];
|
||||
add_motor(motor.motor_num, motor.angle_degrees, motor.yaw_factor, motor.testing_order);
|
||||
add_motor(i, motor.angle_degrees, motor.yaw_factor, motor.testing_order);
|
||||
}
|
||||
}
|
||||
void AP_MotorsMatrix::add_motors_raw(const struct MotorDefRaw *motors, uint8_t num_motors)
|
||||
{
|
||||
for (uint8_t i=0; i<num_motors; i++) {
|
||||
const auto &m = motors[i];
|
||||
add_motor_raw(m.motor_num, m.roll_fac, m.pitch_fac, m.yaw_fac, m.testing_order);
|
||||
add_motor_raw(i, m.roll_fac, m.pitch_fac, m.yaw_fac, m.testing_order);
|
||||
}
|
||||
}
|
||||
|
||||
@ -594,10 +594,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_PLUS: {
|
||||
_frame_type_string = "PLUS";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -605,10 +605,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_X: {
|
||||
_frame_type_string = "X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -617,10 +617,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_NYT_PLUS: {
|
||||
_frame_type_string = "NYT_PLUS";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 90, 0, 2 },
|
||||
{ AP_MOTORS_MOT_2, -90, 0, 4 },
|
||||
{ AP_MOTORS_MOT_3, 0, 0, 1 },
|
||||
{ AP_MOTORS_MOT_4, 180, 0, 3 },
|
||||
{ 90, 0, 2 },
|
||||
{ -90, 0, 4 },
|
||||
{ 0, 0, 1 },
|
||||
{ 180, 0, 3 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -628,10 +628,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_NYT_X: {
|
||||
_frame_type_string = "NYT_X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, 0, 1 },
|
||||
{ AP_MOTORS_MOT_2, -135, 0, 3 },
|
||||
{ AP_MOTORS_MOT_3, -45, 0, 4 },
|
||||
{ AP_MOTORS_MOT_4, 135, 0, 2 },
|
||||
{ 45, 0, 1 },
|
||||
{ -135, 0, 3 },
|
||||
{ -45, 0, 4 },
|
||||
{ 135, 0, 2 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -642,10 +642,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// see: https://fpvfrenzy.com/betaflight-motor-order/
|
||||
_frame_type_string = "BF_X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -654,10 +654,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// betaflight quad X order, reversed motors
|
||||
_frame_type_string = "X_REV";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -667,10 +667,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// see https://forum44.djicdn.com/data/attachment/forum/201711/26/172348bppvtt1ot1nrtp5j.jpg
|
||||
_frame_type_string = "DJI_X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -680,10 +680,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// matching test order
|
||||
_frame_type_string = "CW_X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -691,10 +691,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_V: {
|
||||
_frame_type_string = "V";
|
||||
static const AP_MotorsMatrix::MotorDef motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, 0.7981f, 1 },
|
||||
{ AP_MOTORS_MOT_2, -135, 1.0000f, 3 },
|
||||
{ AP_MOTORS_MOT_3, -45, -0.7981f, 4 },
|
||||
{ AP_MOTORS_MOT_4, 135, -1.0000f, 2 },
|
||||
{ 45, 0.7981f, 1 },
|
||||
{ -135, 1.0000f, 3 },
|
||||
{ -45, -0.7981f, 4 },
|
||||
{ 135, -1.0000f, 2 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -703,10 +703,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// H frame set-up - same as X but motors spin in opposite directiSons
|
||||
_frame_type_string = "H";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -758,10 +758,10 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// plus with reversed motor directions
|
||||
_frame_type_string = "PLUSREV";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -781,12 +781,12 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_PLUS: {
|
||||
_frame_type_string = "PLUS";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_3, -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_5, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -794,12 +794,12 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_X: {
|
||||
_frame_type_string = "X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_3, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ AP_MOTORS_MOT_4, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_6, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -808,12 +808,12 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// H is same as X except middle motors are closer to center
|
||||
_frame_type_string = "H";
|
||||
static const AP_MotorsMatrix::MotorDefRaw motors[] {
|
||||
{ AP_MOTORS_MOT_1, -1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_2, 1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_3, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ AP_MOTORS_MOT_4, -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_5, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_6, 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ -1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
};
|
||||
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -821,12 +821,12 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_DJI_X: {
|
||||
_frame_type_string = "DJI_X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ AP_MOTORS_MOT_3, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_4, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_5, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_6, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -834,12 +834,12 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_CW_X: {
|
||||
_frame_type_string = "CW_X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_3, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_4, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_5, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_6, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -859,14 +859,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_PLUS: {
|
||||
_frame_type_string = "PLUS";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ AP_MOTORS_MOT_3, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ AP_MOTORS_MOT_7, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
};
|
||||
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
@ -875,14 +875,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_X: {
|
||||
_frame_type_string = "X";
|
||||
static const AP_MotorsMatrix::MotorDef motors[] {
|
||||
{ AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ AP_MOTORS_MOT_3, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_4, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_5, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ AP_MOTORS_MOT_6, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ AP_MOTORS_MOT_7, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ AP_MOTORS_MOT_8, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -890,14 +890,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_V: {
|
||||
_frame_type_string = "V";
|
||||
static const AP_MotorsMatrix::MotorDefRaw motors[] {
|
||||
{ AP_MOTORS_MOT_1, 0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ AP_MOTORS_MOT_2, -0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ AP_MOTORS_MOT_3, 0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ AP_MOTORS_MOT_4, -0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_5, 1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ AP_MOTORS_MOT_6, -0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_7, -1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_8, 0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ 0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ -0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ 0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ -0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ 1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ -0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ -1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ 0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
};
|
||||
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -905,14 +905,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_H: {
|
||||
_frame_type_string = "H";
|
||||
static const AP_MotorsMatrix::MotorDefRaw motors[] {
|
||||
{ AP_MOTORS_MOT_1, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ AP_MOTORS_MOT_3, -1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_4, -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_5, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ AP_MOTORS_MOT_6, 1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ AP_MOTORS_MOT_7, 1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ AP_MOTORS_MOT_8, -1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ -1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ 1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ 1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ -1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
};
|
||||
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -920,14 +920,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_I: {
|
||||
_frame_type_string = "I";
|
||||
static const AP_MotorsMatrix::MotorDefRaw motors[] {
|
||||
{ AP_MOTORS_MOT_1, 0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ AP_MOTORS_MOT_3, 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_4, 0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_5, -0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ AP_MOTORS_MOT_6, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ AP_MOTORS_MOT_7, -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ AP_MOTORS_MOT_8, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ 0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ -0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ 0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ -0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
};
|
||||
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -935,14 +935,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_DJI_X: {
|
||||
_frame_type_string = "DJI_X";
|
||||
static const AP_MotorsMatrix::MotorDef motors[] {
|
||||
{ AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ AP_MOTORS_MOT_3, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ AP_MOTORS_MOT_4, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ AP_MOTORS_MOT_5, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_6, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_7, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_8, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -950,14 +950,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_CW_X: {
|
||||
_frame_type_string = "CW_X";
|
||||
static const AP_MotorsMatrix::MotorDef motors[] {
|
||||
{ AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_3, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_4, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_5, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_6, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ AP_MOTORS_MOT_7, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ AP_MOTORS_MOT_8, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -977,14 +977,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_PLUS: {
|
||||
_frame_type_string = "PLUS";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ AP_MOTORS_MOT_3, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_4, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ AP_MOTORS_MOT_5, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ AP_MOTORS_MOT_6, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_7, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -992,14 +992,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_X: {
|
||||
_frame_type_string = "X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1007,14 +1007,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_V: {
|
||||
_frame_type_string = "V";
|
||||
static const AP_MotorsMatrix::MotorDef motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, 0.7981f, 1 },
|
||||
{ AP_MOTORS_MOT_2, -45, -0.7981f, 7 },
|
||||
{ AP_MOTORS_MOT_3, -135, 1.0000f, 5 },
|
||||
{ AP_MOTORS_MOT_4, 135, -1.0000f, 3 },
|
||||
{ AP_MOTORS_MOT_5, -45, 0.7981f, 8 },
|
||||
{ AP_MOTORS_MOT_6, 45, -0.7981f, 2 },
|
||||
{ AP_MOTORS_MOT_7, 135, 1.0000f, 4 },
|
||||
{ AP_MOTORS_MOT_8, -135, -1.0000f, 6 },
|
||||
{ 45, 0.7981f, 1 },
|
||||
{ -45, -0.7981f, 7 },
|
||||
{ -135, 1.0000f, 5 },
|
||||
{ 135, -1.0000f, 3 },
|
||||
{ -45, 0.7981f, 8 },
|
||||
{ 45, -0.7981f, 2 },
|
||||
{ 135, 1.0000f, 4 },
|
||||
{ -135, -1.0000f, 6 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1023,14 +1023,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// H frame set-up - same as X but motors spin in opposite directions
|
||||
_frame_type_string = "H";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1038,14 +1038,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_CW_X:
|
||||
_frame_type_string = "CW_X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_3, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_5, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ AP_MOTORS_MOT_7, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ AP_MOTORS_MOT_8, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 },
|
||||
{ -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1064,18 +1064,18 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_PLUS: {
|
||||
_frame_type_string = "PLUS";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, // forward-top
|
||||
{ AP_MOTORS_MOT_2, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, // forward-bottom
|
||||
{ AP_MOTORS_MOT_3, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, // forward-right-top
|
||||
{ AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, // forward-right-bottom
|
||||
{ AP_MOTORS_MOT_5, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, // back-right-top
|
||||
{ AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, // back-right-bottom
|
||||
{ AP_MOTORS_MOT_7, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, // back-top
|
||||
{ AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, // back-bottom
|
||||
{ AP_MOTORS_MOT_9, -120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, // back-left-top
|
||||
{ AP_MOTORS_MOT_10, -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, // back-left-bottom
|
||||
{ AP_MOTORS_MOT_11, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11 }, // forward-left-top
|
||||
{ AP_MOTORS_MOT_12, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12 }, // forward-left-bottom
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, // forward-top
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, // forward-bottom
|
||||
{ 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, // forward-right-top
|
||||
{ 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, // forward-right-bottom
|
||||
{ 120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, // back-right-top
|
||||
{ 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, // back-right-bottom
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, // back-top
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, // back-bottom
|
||||
{ -120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, // back-left-top
|
||||
{ -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, // back-left-bottom
|
||||
{ -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11 }, // forward-left-top
|
||||
{ -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12 }, // forward-left-bottom
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1083,18 +1083,18 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_X: {
|
||||
_frame_type_string = "X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, // forward-right-top
|
||||
{ AP_MOTORS_MOT_2, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, // forward-right-bottom
|
||||
{ AP_MOTORS_MOT_3, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, // right-top
|
||||
{ AP_MOTORS_MOT_4, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, // right-bottom
|
||||
{ AP_MOTORS_MOT_5, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, // back-right-top
|
||||
{ AP_MOTORS_MOT_6, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, // back-right-bottom
|
||||
{ AP_MOTORS_MOT_7, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, // back-left-top
|
||||
{ AP_MOTORS_MOT_8, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, // back-left-bottom
|
||||
{ AP_MOTORS_MOT_9, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, // left-top
|
||||
{ AP_MOTORS_MOT_10, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, // left-bottom
|
||||
{ AP_MOTORS_MOT_11, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11 }, // forward-left-top
|
||||
{ AP_MOTORS_MOT_12, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12 }, // forward-left-bottom
|
||||
{ 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, // forward-right-top
|
||||
{ 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, // forward-right-bottom
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, // right-top
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, // right-bottom
|
||||
{ 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, // back-right-top
|
||||
{ 150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, // back-right-bottom
|
||||
{ -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, // back-left-top
|
||||
{ -150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, // back-left-bottom
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, // left-top
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, // left-bottom
|
||||
{ -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11 }, // forward-left-top
|
||||
{ -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12 }, // forward-left-bottom
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1115,12 +1115,12 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise
|
||||
_frame_type_string = "Y6B";
|
||||
static const AP_MotorsMatrix::MotorDefRaw motors[] {
|
||||
{ AP_MOTORS_MOT_1, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_2, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_3, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ AP_MOTORS_MOT_4, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ AP_MOTORS_MOT_5, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ AP_MOTORS_MOT_6, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 },
|
||||
{ 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 },
|
||||
{ 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
};
|
||||
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1129,12 +1129,12 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// Y6 motor layout for FireFlyY6
|
||||
_frame_type_string = "Y6F";
|
||||
static const AP_MotorsMatrix::MotorDefRaw motors[] {
|
||||
{ AP_MOTORS_MOT_1, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_2, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_3, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_4, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_5, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_6, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
};
|
||||
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1142,12 +1142,12 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
default: {
|
||||
_frame_type_string = "default";
|
||||
static const AP_MotorsMatrix::MotorDefRaw motors[] {
|
||||
{ AP_MOTORS_MOT_1, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ AP_MOTORS_MOT_2, 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ AP_MOTORS_MOT_3, 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ AP_MOTORS_MOT_4, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_5, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ AP_MOTORS_MOT_6, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 },
|
||||
{ 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 },
|
||||
{ 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 },
|
||||
{ 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 },
|
||||
{ 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
};
|
||||
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1162,16 +1162,16 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_PLUS: {
|
||||
_frame_type_string = "PLUS";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_3, 72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_4, 108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_5, 144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_6, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ AP_MOTORS_MOT_7, -144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ AP_MOTORS_MOT_8, -108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ AP_MOTORS_MOT_9, -72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 },
|
||||
{ AP_MOTORS_MOT_10, -36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 },
|
||||
{ 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ 108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ -144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ -108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ -72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 },
|
||||
{ -36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
@ -1179,16 +1179,16 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
case MOTOR_FRAME_TYPE_X: {
|
||||
_frame_type_string = "X";
|
||||
static const AP_MotorsMatrix::MotorDefInt motors[] {
|
||||
{ AP_MOTORS_MOT_1, 18, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ AP_MOTORS_MOT_2, 54, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ AP_MOTORS_MOT_3, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ AP_MOTORS_MOT_4, 126, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ AP_MOTORS_MOT_5, 162, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ AP_MOTORS_MOT_6, -162, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ AP_MOTORS_MOT_7, -126, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ AP_MOTORS_MOT_8, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ AP_MOTORS_MOT_9, -54, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 },
|
||||
{ AP_MOTORS_MOT_10, -18, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 },
|
||||
{ 18, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
|
||||
{ 54, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
|
||||
{ 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 },
|
||||
{ 126, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 },
|
||||
{ 162, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 },
|
||||
{ -162, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 },
|
||||
{ -126, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 },
|
||||
{ -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 },
|
||||
{ -54, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 },
|
||||
{ -18, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 },
|
||||
};
|
||||
add_motors(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
|
@ -90,14 +90,12 @@ public:
|
||||
// the arguments to add_motor - with the exception of the type,
|
||||
// for compactness.
|
||||
struct MotorDefInt {
|
||||
int8_t motor_num;
|
||||
int16_t angle_degrees;
|
||||
int8_t yaw_factor;
|
||||
uint8_t testing_order;
|
||||
};
|
||||
// same structure, but with floats.
|
||||
struct MotorDef {
|
||||
int8_t motor_num;
|
||||
float angle_degrees;
|
||||
float yaw_factor;
|
||||
uint8_t testing_order;
|
||||
@ -113,7 +111,6 @@ public:
|
||||
// factor as that is only used in the scripting binding, not in
|
||||
// the static motors at the moment.
|
||||
struct MotorDefRaw {
|
||||
int8_t motor_num;
|
||||
float roll_fac;
|
||||
float pitch_fac;
|
||||
float yaw_fac;
|
||||
|
Loading…
Reference in New Issue
Block a user