2013-05-29 20:51:34 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
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/>.
|
|
|
|
*/
|
|
|
|
|
2012-04-02 05:26:37 -03:00
|
|
|
/*
|
2012-08-17 03:20:26 -03:00
|
|
|
* AP_MotorsQuad.cpp - ArduCopter motors library
|
|
|
|
* Code by RandyMackay. DIYDrones.com
|
|
|
|
*
|
|
|
|
*/
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
#include "AP_MotorsQuad.h"
|
|
|
|
|
|
|
|
// setup_motors - configures the motors for a quad
|
|
|
|
void AP_MotorsQuad::setup_motors()
|
|
|
|
{
|
2012-08-17 03:20:26 -03:00
|
|
|
// call parent
|
|
|
|
AP_MotorsMatrix::setup_motors();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:26 -03:00
|
|
|
// hard coded config for supported frames
|
2013-09-12 10:27:44 -03:00
|
|
|
if( _flags.frame_orientation == AP_MOTORS_PLUS_FRAME ) {
|
2012-08-17 03:20:26 -03:00
|
|
|
// plus frame set-up
|
2013-04-25 05:52:19 -03:00
|
|
|
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);
|
2013-05-14 07:01:53 -03:00
|
|
|
|
2013-09-12 10:27:44 -03:00
|
|
|
}else if( _flags.frame_orientation == AP_MOTORS_V_FRAME ) {
|
2013-05-03 11:13:40 -03:00
|
|
|
// V frame set-up
|
2015-04-24 00:51:54 -03:00
|
|
|
add_motor(AP_MOTORS_MOT_1, 45, 0.7981f, 1);
|
|
|
|
add_motor(AP_MOTORS_MOT_2, -135, 1.0000f, 3);
|
|
|
|
add_motor(AP_MOTORS_MOT_3, -45, -0.7981f, 4);
|
|
|
|
add_motor(AP_MOTORS_MOT_4, 135, -1.0000f, 2);
|
2013-05-14 07:01:53 -03:00
|
|
|
|
2013-09-12 10:27:44 -03:00
|
|
|
}else if( _flags.frame_orientation == AP_MOTORS_H_FRAME ) {
|
2013-05-14 07:01:53 -03:00
|
|
|
// 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);
|
2014-08-18 02:25:24 -03:00
|
|
|
}else if(_flags.frame_orientation == AP_MOTORS_VTAIL_FRAME) {
|
|
|
|
/*
|
|
|
|
Tested with: Lynxmotion Hunter Vtail 400
|
|
|
|
- inverted rear outward blowing motors (at a 40 degree angle)
|
|
|
|
- should also work with non-inverted rear outward blowing motors
|
|
|
|
- no roll in rear motors
|
|
|
|
- no yaw in front motors
|
|
|
|
- should fly like some mix between a tricopter and X Quadcopter
|
2013-05-14 07:01:53 -03:00
|
|
|
|
2014-08-18 02:25:24 -03:00
|
|
|
Roll control comes only from the front motors, Yaw control only from the rear motors.
|
|
|
|
Roll & Pitch factor is measured by the angle away from the top of the forward axis to each arm.
|
2014-04-01 23:51:41 -03:00
|
|
|
|
2014-08-18 02:25:24 -03:00
|
|
|
Note: if we want the front motors to help with yaw,
|
|
|
|
motors 1's yaw factor should be changed to sin(radians(40)). Where "40" is the vtail angle
|
|
|
|
motors 3's yaw factor should be changed to -sin(radians(40))
|
|
|
|
*/
|
2014-04-01 23:51:41 -03:00
|
|
|
|
2014-08-18 02:25:24 -03:00
|
|
|
add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1);
|
|
|
|
add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
|
|
|
|
add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4);
|
|
|
|
add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
|
|
|
|
} else if (_flags.frame_orientation == AP_MOTORS_ATAIL_FRAME) {
|
|
|
|
/*
|
|
|
|
The A-Shaped VTail is the exact same as a V-Shaped VTail, with one difference:
|
|
|
|
- The Yaw factors are reversed, because the rear motors are facing different directions
|
2014-04-01 23:51:41 -03:00
|
|
|
|
2014-08-18 02:25:24 -03:00
|
|
|
With V-Shaped VTails, the props make a V-Shape when spinning, but with
|
|
|
|
A-Shaped VTails, the props make an A-Shape when spinning.
|
|
|
|
- Rear thrust on a V-Shaped V-Tail Quad is outward
|
|
|
|
- Rear thrust on an A-Shaped V-Tail Quad is inward
|
2014-04-01 23:51:41 -03:00
|
|
|
|
2014-08-18 02:25:24 -03:00
|
|
|
Still functions the same as the V-Shaped VTail mixing below:
|
|
|
|
- Yaw control is entirely in the rear motors
|
|
|
|
- Roll is is entirely in the front motors
|
|
|
|
*/
|
|
|
|
add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1);
|
|
|
|
add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
|
|
|
|
add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4);
|
|
|
|
add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
|
2015-11-23 19:18:09 -04:00
|
|
|
} else if ( _flags.frame_orientation == AP_MOTORS_QUADPLANE ) {
|
|
|
|
// quadplane frame set-up, X arrangement on motors 5 to 8
|
|
|
|
add_motor(AP_MOTORS_MOT_5, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
|
|
|
|
add_motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
|
|
|
|
add_motor(AP_MOTORS_MOT_7, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
|
|
|
|
add_motor(AP_MOTORS_MOT_8, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
|
2012-08-17 03:20:26 -03:00
|
|
|
}else{
|
|
|
|
// X frame set-up
|
2013-04-25 05:52:19 -03:00
|
|
|
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);
|
2012-08-17 03:20:26 -03:00
|
|
|
}
|
2012-04-02 05:26:37 -03:00
|
|
|
}
|