mirror of https://github.com/ArduPilot/ardupilot
61 lines
2.5 KiB
C++
61 lines
2.5 KiB
C++
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
/*
|
|
This program is free software: you can redistribute it and/or modify
|
|
it under the terms of the GNU General Public License as published by
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
(at your option) any later version.
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
GNU General Public License for more details.
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
*/
|
|
|
|
/*
|
|
* AP_MotorsQuad.cpp - ArduCopter motors library
|
|
* Code by RandyMackay. DIYDrones.com
|
|
*
|
|
*/
|
|
|
|
#include "AP_MotorsQuad.h"
|
|
|
|
// setup_motors - configures the motors for a quad
|
|
void AP_MotorsQuad::setup_motors()
|
|
{
|
|
// call parent
|
|
AP_MotorsMatrix::setup_motors();
|
|
|
|
// hard coded config for supported frames
|
|
if( _frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
|
// plus frame set-up
|
|
add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
|
|
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
|
|
add_motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
|
|
add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
|
|
|
|
}else if( _frame_orientation == AP_MOTORS_V_FRAME ) {
|
|
// V frame set-up
|
|
add_motor(AP_MOTORS_MOT_1, 45, 0.7981, 1);
|
|
add_motor(AP_MOTORS_MOT_2, -135, 1.0000, 3);
|
|
add_motor(AP_MOTORS_MOT_3, -45, -0.7981, 4);
|
|
add_motor(AP_MOTORS_MOT_4, 135, -1.0000, 2);
|
|
|
|
}else if( _frame_orientation == AP_MOTORS_H_FRAME ) {
|
|
// H frame set-up - same as X but motors spin in opposite directiSons
|
|
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
|
|
add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
|
|
add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
|
|
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
|
|
|
|
}else{
|
|
// X frame set-up
|
|
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
|
|
add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
|
|
add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
|
|
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
|
|
}
|
|
}
|