mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
AP_Motors: remove unnecessary opposite_motor array (no longer needed with new stability patch)
This commit is contained in:
parent
34e18ae12a
commit
3aca61cefb
@ -19,19 +19,19 @@ void AP_MotorsHexa::setup_motors()
|
|||||||
// hard coded config for supported frames
|
// hard coded config for supported frames
|
||||||
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
||||||
// plus frame set-up
|
// plus frame set-up
|
||||||
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_2, 1);
|
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_MOTOR_CW, 1);
|
||||||
add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_1, 4);
|
add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_MOTOR_CCW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_3,-120, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_4, 5);
|
add_motor(AP_MOTORS_MOT_3,-120, AP_MOTORS_MATRIX_MOTOR_CW, 5);
|
||||||
add_motor(AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_3, 2);
|
add_motor(AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_MOTOR_CCW, 2);
|
||||||
add_motor(AP_MOTORS_MOT_5, -60, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_6, 6);
|
add_motor(AP_MOTORS_MOT_5, -60, AP_MOTORS_MATRIX_MOTOR_CCW, 6);
|
||||||
add_motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_5, 3);
|
add_motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_MOTOR_CW, 3);
|
||||||
}else{
|
}else{
|
||||||
// X frame set-up
|
// X frame set-up
|
||||||
add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_2, 2);
|
add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_MOTOR_CW, 2);
|
||||||
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_1, 5);
|
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_MOTOR_CCW, 5);
|
||||||
add_motor(AP_MOTORS_MOT_3, -30, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_4, 6);
|
add_motor(AP_MOTORS_MOT_3, -30, AP_MOTORS_MATRIX_MOTOR_CW, 6);
|
||||||
add_motor(AP_MOTORS_MOT_4, 150, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_3, 3);
|
add_motor(AP_MOTORS_MOT_4, 150, AP_MOTORS_MATRIX_MOTOR_CCW, 3);
|
||||||
add_motor(AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_6, 1);
|
add_motor(AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_MOTOR_CCW, 1);
|
||||||
add_motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_5, 4);
|
add_motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_MOTOR_CW, 4);
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -15,20 +15,12 @@ extern const AP_HAL::HAL& hal;
|
|||||||
// Init
|
// Init
|
||||||
void AP_MotorsMatrix::Init()
|
void AP_MotorsMatrix::Init()
|
||||||
{
|
{
|
||||||
int8_t i;
|
|
||||||
|
|
||||||
// call parent Init function to set-up throttle curve
|
// call parent Init function to set-up throttle curve
|
||||||
AP_Motors::Init();
|
AP_Motors::Init();
|
||||||
|
|
||||||
// setup the motors
|
// setup the motors
|
||||||
setup_motors();
|
setup_motors();
|
||||||
|
|
||||||
// double check that opposite motor definitions are ok
|
|
||||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
|
||||||
if( opposite_motor[i] <= 0 || opposite_motor[i] >= AP_MOTORS_MAX_NUM_MOTORS || !motor_enabled[opposite_motor[i]] )
|
|
||||||
opposite_motor[i] = AP_MOTORS_MATRIX_MOTOR_UNDEFINED;
|
|
||||||
}
|
|
||||||
|
|
||||||
// enable fast channels or instant pwm
|
// enable fast channels or instant pwm
|
||||||
set_update_rate(_speed_hz);
|
set_update_rate(_speed_hz);
|
||||||
}
|
}
|
||||||
@ -328,7 +320,7 @@ void AP_MotorsMatrix::output_test()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// add_motor
|
// add_motor
|
||||||
void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, int8_t opposite_motor_num, int8_t testing_order)
|
void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, int8_t testing_order)
|
||||||
{
|
{
|
||||||
// ensure valid motor number is provided
|
// ensure valid motor number is provided
|
||||||
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
||||||
@ -344,13 +336,6 @@ void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitc
|
|||||||
_pitch_factor[motor_num] = pitch_fac;
|
_pitch_factor[motor_num] = pitch_fac;
|
||||||
_yaw_factor[motor_num] = yaw_fac;
|
_yaw_factor[motor_num] = yaw_fac;
|
||||||
|
|
||||||
// set opposite motor after checking it's somewhat valid
|
|
||||||
if( opposite_motor_num == AP_MOTORS_MATRIX_MOTOR_UNDEFINED || (opposite_motor_num >=0 && opposite_motor_num < AP_MOTORS_MAX_NUM_MOTORS) ) {
|
|
||||||
opposite_motor[motor_num] = opposite_motor_num;
|
|
||||||
}else{
|
|
||||||
opposite_motor[motor_num] = AP_MOTORS_MATRIX_MOTOR_UNDEFINED;
|
|
||||||
}
|
|
||||||
|
|
||||||
// set order that motor appears in test
|
// set order that motor appears in test
|
||||||
if( testing_order == AP_MOTORS_MATRIX_ORDER_UNDEFINED ) {
|
if( testing_order == AP_MOTORS_MATRIX_ORDER_UNDEFINED ) {
|
||||||
test_order[motor_num] = motor_num;
|
test_order[motor_num] = motor_num;
|
||||||
@ -361,7 +346,7 @@ void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitc
|
|||||||
}
|
}
|
||||||
|
|
||||||
// add_motor using just position and prop direction
|
// add_motor using just position and prop direction
|
||||||
void AP_MotorsMatrix::add_motor(int8_t motor_num, float angle_degrees, int8_t direction, int8_t opposite_motor_num, int8_t testing_order)
|
void AP_MotorsMatrix::add_motor(int8_t motor_num, float angle_degrees, int8_t direction, int8_t testing_order)
|
||||||
{
|
{
|
||||||
// call raw motor set-up method
|
// call raw motor set-up method
|
||||||
add_motor_raw(
|
add_motor_raw(
|
||||||
@ -369,7 +354,6 @@ void AP_MotorsMatrix::add_motor(int8_t motor_num, float angle_degrees, int8_t di
|
|||||||
cos(radians(angle_degrees + 90)), // roll factor
|
cos(radians(angle_degrees + 90)), // roll factor
|
||||||
cos(radians(angle_degrees)), // pitch factor
|
cos(radians(angle_degrees)), // pitch factor
|
||||||
(float)direction, // yaw factor
|
(float)direction, // yaw factor
|
||||||
opposite_motor_num,
|
|
||||||
testing_order);
|
testing_order);
|
||||||
|
|
||||||
}
|
}
|
||||||
@ -377,8 +361,6 @@ void AP_MotorsMatrix::add_motor(int8_t motor_num, float angle_degrees, int8_t di
|
|||||||
// remove_motor - disabled motor and clears all roll, pitch, throttle factors for this motor
|
// remove_motor - disabled motor and clears all roll, pitch, throttle factors for this motor
|
||||||
void AP_MotorsMatrix::remove_motor(int8_t motor_num)
|
void AP_MotorsMatrix::remove_motor(int8_t motor_num)
|
||||||
{
|
{
|
||||||
int8_t i;
|
|
||||||
|
|
||||||
// ensure valid motor number is provided
|
// ensure valid motor number is provided
|
||||||
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
||||||
|
|
||||||
@ -391,13 +373,6 @@ void AP_MotorsMatrix::remove_motor(int8_t motor_num)
|
|||||||
_roll_factor[motor_num] = 0;
|
_roll_factor[motor_num] = 0;
|
||||||
_pitch_factor[motor_num] = 0;
|
_pitch_factor[motor_num] = 0;
|
||||||
_yaw_factor[motor_num] = 0;
|
_yaw_factor[motor_num] = 0;
|
||||||
opposite_motor[motor_num] = AP_MOTORS_MATRIX_MOTOR_UNDEFINED;
|
|
||||||
}
|
|
||||||
|
|
||||||
// if another motor has referred to this motor as it's opposite, remove that reference
|
|
||||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
|
||||||
if( opposite_motor[i] == motor_num )
|
|
||||||
opposite_motor[i] = AP_MOTORS_MATRIX_MOTOR_UNDEFINED;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -54,7 +54,7 @@ public:
|
|||||||
virtual void output_min();
|
virtual void output_min();
|
||||||
|
|
||||||
// add_motor using just position and prop direction
|
// add_motor using just position and prop direction
|
||||||
virtual void add_motor(int8_t motor_num, float angle_degrees, int8_t direction, int8_t opposite_motor_num = AP_MOTORS_MATRIX_MOTOR_UNDEFINED, int8_t testing_order = AP_MOTORS_MATRIX_ORDER_UNDEFINED);
|
virtual void add_motor(int8_t motor_num, float angle_degrees, int8_t direction, int8_t testing_order = AP_MOTORS_MATRIX_ORDER_UNDEFINED);
|
||||||
|
|
||||||
// remove_motor
|
// remove_motor
|
||||||
virtual void remove_motor(int8_t motor_num);
|
virtual void remove_motor(int8_t motor_num);
|
||||||
@ -68,7 +68,6 @@ public:
|
|||||||
};
|
};
|
||||||
|
|
||||||
// matrix
|
// matrix
|
||||||
AP_Int8 opposite_motor[AP_MOTORS_MAX_NUM_MOTORS]; // motor number of the opposite motor
|
|
||||||
AP_Int8 test_order[AP_MOTORS_MAX_NUM_MOTORS]; // order of the motors in the test sequence
|
AP_Int8 test_order[AP_MOTORS_MAX_NUM_MOTORS]; // order of the motors in the test sequence
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
@ -77,7 +76,7 @@ protected:
|
|||||||
virtual void output_disarmed();
|
virtual void output_disarmed();
|
||||||
|
|
||||||
// add_motor using raw roll, pitch, throttle and yaw factors
|
// add_motor using raw roll, pitch, throttle and yaw factors
|
||||||
virtual void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, int8_t opposite_motor_num = AP_MOTORS_MATRIX_MOTOR_UNDEFINED, int8_t testing_order = AP_MOTORS_MATRIX_ORDER_UNDEFINED);
|
virtual void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, int8_t testing_order = AP_MOTORS_MATRIX_ORDER_UNDEFINED);
|
||||||
|
|
||||||
int8_t _num_motors; // not a very useful variable as you really need to check the motor_enabled array to see which motors are enabled
|
int8_t _num_motors; // not a very useful variable as you really need to check the motor_enabled array to see which motors are enabled
|
||||||
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to roll
|
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to roll
|
||||||
|
@ -19,35 +19,35 @@ void AP_MotorsOcta::setup_motors()
|
|||||||
// hard coded config for supported frames
|
// hard coded config for supported frames
|
||||||
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
||||||
// plus frame set-up
|
// plus frame set-up
|
||||||
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_2, 1);
|
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_MOTOR_CW, 1);
|
||||||
add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_1, 5);
|
add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_MOTOR_CW, 5);
|
||||||
add_motor(AP_MOTORS_MOT_3, 45, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_6, 2);
|
add_motor(AP_MOTORS_MOT_3, 45, AP_MOTORS_MATRIX_MOTOR_CCW, 2);
|
||||||
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_5, 4);
|
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_MOTOR_CCW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_4, 8);
|
add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_MOTOR_CCW, 8);
|
||||||
add_motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_3, 6);
|
add_motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_MOTOR_CCW, 6);
|
||||||
add_motor(AP_MOTORS_MOT_7, -90, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_8, 7);
|
add_motor(AP_MOTORS_MOT_7, -90, AP_MOTORS_MATRIX_MOTOR_CW, 7);
|
||||||
add_motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_7, 3);
|
add_motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_MOTOR_CW, 3);
|
||||||
|
|
||||||
}else if( _frame_orientation == AP_MOTORS_V_FRAME ) {
|
}else if( _frame_orientation == AP_MOTORS_V_FRAME ) {
|
||||||
// V frame set-up
|
// V frame set-up
|
||||||
add_motor_raw(AP_MOTORS_MOT_1, 1.0, 0.34, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_2, 7);
|
add_motor_raw(AP_MOTORS_MOT_1, 1.0, 0.34, AP_MOTORS_MATRIX_MOTOR_CW, 7);
|
||||||
add_motor_raw(AP_MOTORS_MOT_2, -1.0, -0.32, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_1, 3);
|
add_motor_raw(AP_MOTORS_MOT_2, -1.0, -0.32, AP_MOTORS_MATRIX_MOTOR_CW, 3);
|
||||||
add_motor_raw(AP_MOTORS_MOT_3, 1.0, -0.32, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_6, 6);
|
add_motor_raw(AP_MOTORS_MOT_3, 1.0, -0.32, AP_MOTORS_MATRIX_MOTOR_CCW, 6);
|
||||||
add_motor_raw(AP_MOTORS_MOT_4, -0.5, -1.0, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_5, 4);
|
add_motor_raw(AP_MOTORS_MOT_4, -0.5, -1.0, AP_MOTORS_MATRIX_MOTOR_CCW, 4);
|
||||||
add_motor_raw(AP_MOTORS_MOT_5, 1.0, 1.0, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_4, 8);
|
add_motor_raw(AP_MOTORS_MOT_5, 1.0, 1.0, AP_MOTORS_MATRIX_MOTOR_CCW, 8);
|
||||||
add_motor_raw(AP_MOTORS_MOT_6, -1.0, 0.34, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_3, 2);
|
add_motor_raw(AP_MOTORS_MOT_6, -1.0, 0.34, AP_MOTORS_MATRIX_MOTOR_CCW, 2);
|
||||||
add_motor_raw(AP_MOTORS_MOT_7, -1.0, 1.0, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_8, 1);
|
add_motor_raw(AP_MOTORS_MOT_7, -1.0, 1.0, AP_MOTORS_MATRIX_MOTOR_CW, 1);
|
||||||
add_motor_raw(AP_MOTORS_MOT_8, 0.5, -1.0, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_7, 5);
|
add_motor_raw(AP_MOTORS_MOT_8, 0.5, -1.0, AP_MOTORS_MATRIX_MOTOR_CW, 5);
|
||||||
|
|
||||||
}else {
|
}else {
|
||||||
// X frame set-up
|
// X frame set-up
|
||||||
add_motor(AP_MOTORS_MOT_1, 22.5, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_2, 1);
|
add_motor(AP_MOTORS_MOT_1, 22.5, AP_MOTORS_MATRIX_MOTOR_CW, 1);
|
||||||
add_motor(AP_MOTORS_MOT_2, -157.5, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_1, 5);
|
add_motor(AP_MOTORS_MOT_2, -157.5, AP_MOTORS_MATRIX_MOTOR_CW, 5);
|
||||||
add_motor(AP_MOTORS_MOT_3, 67.5, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_6, 2);
|
add_motor(AP_MOTORS_MOT_3, 67.5, AP_MOTORS_MATRIX_MOTOR_CCW, 2);
|
||||||
add_motor(AP_MOTORS_MOT_4, 157.5, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_5, 4);
|
add_motor(AP_MOTORS_MOT_4, 157.5, AP_MOTORS_MATRIX_MOTOR_CCW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_5, -22.5, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_4, 8);
|
add_motor(AP_MOTORS_MOT_5, -22.5, AP_MOTORS_MATRIX_MOTOR_CCW, 8);
|
||||||
add_motor(AP_MOTORS_MOT_6, -112.5, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_3, 6);
|
add_motor(AP_MOTORS_MOT_6, -112.5, AP_MOTORS_MATRIX_MOTOR_CCW, 6);
|
||||||
add_motor(AP_MOTORS_MOT_7, -67.5, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_8, 7);
|
add_motor(AP_MOTORS_MOT_7, -67.5, AP_MOTORS_MATRIX_MOTOR_CW, 7);
|
||||||
add_motor(AP_MOTORS_MOT_8, 112.5, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_7, 3);
|
add_motor(AP_MOTORS_MOT_8, 112.5, AP_MOTORS_MATRIX_MOTOR_CW, 3);
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -19,23 +19,23 @@ void AP_MotorsOctaQuad::setup_motors()
|
|||||||
// hard coded config for supported frames
|
// hard coded config for supported frames
|
||||||
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
||||||
// plus frame set-up
|
// plus frame set-up
|
||||||
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_3, 1);
|
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_MOTOR_CCW, 1);
|
||||||
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_4, 7);
|
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_MOTOR_CW, 7);
|
||||||
add_motor(AP_MOTORS_MOT_3, 180, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_1, 5);
|
add_motor(AP_MOTORS_MOT_3, 180, AP_MOTORS_MATRIX_MOTOR_CCW, 5);
|
||||||
add_motor(AP_MOTORS_MOT_4, 90, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_2, 4);
|
add_motor(AP_MOTORS_MOT_4, 90, AP_MOTORS_MATRIX_MOTOR_CW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_5, -90, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_7, 8);
|
add_motor(AP_MOTORS_MOT_5, -90, AP_MOTORS_MATRIX_MOTOR_CCW, 8);
|
||||||
add_motor(AP_MOTORS_MOT_6, 0, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_8, 2);
|
add_motor(AP_MOTORS_MOT_6, 0, AP_MOTORS_MATRIX_MOTOR_CW, 2);
|
||||||
add_motor(AP_MOTORS_MOT_7, 90, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_5, 4);
|
add_motor(AP_MOTORS_MOT_7, 90, AP_MOTORS_MATRIX_MOTOR_CCW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_6, 6);
|
add_motor(AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_MOTOR_CW, 6);
|
||||||
}else{
|
}else{
|
||||||
// X frame set-up
|
// X frame set-up
|
||||||
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_3, 1);
|
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_MOTOR_CCW, 1);
|
||||||
add_motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_4, 7);
|
add_motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_MOTOR_CW, 7);
|
||||||
add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_1, 5);
|
add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_MOTOR_CCW, 5);
|
||||||
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_2, 4);
|
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_MOTOR_CW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_7, 8);
|
add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_MOTOR_CCW, 8);
|
||||||
add_motor(AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_8, 2);
|
add_motor(AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_MOTOR_CW, 2);
|
||||||
add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_5, 4);
|
add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_MOTOR_CCW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_6, 6);
|
add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_MOTOR_CW, 6);
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -19,15 +19,15 @@ void AP_MotorsQuad::setup_motors()
|
|||||||
// hard coded config for supported frames
|
// hard coded config for supported frames
|
||||||
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
||||||
// plus frame set-up
|
// plus frame set-up
|
||||||
add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_2, 2);
|
add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_MOTOR_CCW, 2);
|
||||||
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_1, 4);
|
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_MOTOR_CCW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_4, 1);
|
add_motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_MOTOR_CW, 1);
|
||||||
add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_3, 3);
|
add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_MOTOR_CW, 3);
|
||||||
}else{
|
}else{
|
||||||
// X frame set-up
|
// X frame set-up
|
||||||
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_2, 1);
|
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_MOTOR_CCW, 1);
|
||||||
add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_1, 3);
|
add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_MOTOR_CCW, 3);
|
||||||
add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_4, 4);
|
add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_MOTOR_CW, 4);
|
||||||
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MOT_3, 2);
|
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_MOTOR_CW, 2);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -17,10 +17,10 @@ void AP_MotorsY6::setup_motors()
|
|||||||
AP_MotorsMatrix::setup_motors();
|
AP_MotorsMatrix::setup_motors();
|
||||||
|
|
||||||
// MultiWii set-up
|
// MultiWii set-up
|
||||||
add_motor_raw(AP_MOTORS_MOT_1, -1.0, 0.666, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MATRIX_MOTOR_UNDEFINED, 2);
|
add_motor_raw(AP_MOTORS_MOT_1, -1.0, 0.666, AP_MOTORS_MATRIX_MOTOR_CCW, 2);
|
||||||
add_motor_raw(AP_MOTORS_MOT_2, 1.0, 0.666, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MATRIX_MOTOR_UNDEFINED, 5);
|
add_motor_raw(AP_MOTORS_MOT_2, 1.0, 0.666, AP_MOTORS_MATRIX_MOTOR_CW, 5);
|
||||||
add_motor_raw(AP_MOTORS_MOT_3, 1.0, 0.666, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MATRIX_MOTOR_UNDEFINED, 6);
|
add_motor_raw(AP_MOTORS_MOT_3, 1.0, 0.666, AP_MOTORS_MATRIX_MOTOR_CCW, 6);
|
||||||
add_motor_raw(AP_MOTORS_MOT_4, 0.0, -1.333, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MATRIX_MOTOR_UNDEFINED, 4);
|
add_motor_raw(AP_MOTORS_MOT_4, 0.0, -1.333, AP_MOTORS_MATRIX_MOTOR_CW, 4);
|
||||||
add_motor_raw(AP_MOTORS_MOT_5, -1.0, 0.666, AP_MOTORS_MATRIX_MOTOR_CW, AP_MOTORS_MATRIX_MOTOR_UNDEFINED, 1);
|
add_motor_raw(AP_MOTORS_MOT_5, -1.0, 0.666, AP_MOTORS_MATRIX_MOTOR_CW, 1);
|
||||||
add_motor_raw(AP_MOTORS_MOT_6, 0.0, -1.333, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MATRIX_MOTOR_UNDEFINED, 3);
|
add_motor_raw(AP_MOTORS_MOT_6, 0.0, -1.333, AP_MOTORS_MATRIX_MOTOR_CCW, 3);
|
||||||
}
|
}
|
Loading…
Reference in New Issue
Block a user