Browse Source
AP_MOTORS_x_FRAME definitions moved to motor_frame_type enum init function and now accepts frame-class and type to perform initial motor setup set_frame_class_and_type allows real-time changing of motor setup initialised_ok flag and accessor records whether setup was successfulmission-4.1.18
23 changed files with 344 additions and 522 deletions
@ -1,51 +0,0 @@
@@ -1,51 +0,0 @@
|
||||
/*
|
||||
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_MotorsHexa.cpp - ArduCopter motors library |
||||
* Code by RandyMackay. DIYDrones.com |
||||
* |
||||
*/ |
||||
|
||||
#include "AP_MotorsHexa.h" |
||||
|
||||
// setup_motors - configures the motors for a hexa
|
||||
void AP_MotorsHexa::setup_motors() |
||||
{ |
||||
// call parent
|
||||
AP_MotorsMatrix::setup_motors(); |
||||
|
||||
// hard coded config for supported frames
|
||||
if( _flags.frame_orientation == AP_MOTORS_PLUS_FRAME ) { |
||||
// plus frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
||||
add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
||||
add_motor(AP_MOTORS_MOT_3,-120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
||||
add_motor(AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
||||
add_motor(AP_MOTORS_MOT_5, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); |
||||
add_motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
||||
}else{ |
||||
// X frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); |
||||
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); |
||||
add_motor(AP_MOTORS_MOT_3, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); |
||||
add_motor(AP_MOTORS_MOT_4, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); |
||||
add_motor(AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); |
||||
add_motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); |
||||
} |
||||
|
||||
// normalise factors to magnitude 0.5
|
||||
normalise_rpy_factors(); |
||||
} |
@ -1,24 +0,0 @@
@@ -1,24 +0,0 @@
|
||||
/// @file AP_MotorsHexa.h
|
||||
/// @brief Motor control class for Hexacopters
|
||||
#pragma once |
||||
|
||||
#include <AP_Common/AP_Common.h> |
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library |
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library |
||||
#include "AP_MotorsMatrix.h" // Parent Motors Matrix library |
||||
|
||||
/// @class AP_MotorsHexa
|
||||
class AP_MotorsHexa : public AP_MotorsMatrix { |
||||
public: |
||||
|
||||
/// Constructor
|
||||
AP_MotorsHexa(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : |
||||
AP_MotorsMatrix(loop_rate, speed_hz) |
||||
{ }; |
||||
|
||||
// setup_motors - configures the motors for a hexa
|
||||
virtual void setup_motors(); |
||||
|
||||
protected: |
||||
|
||||
}; |
@ -1,67 +0,0 @@
@@ -1,67 +0,0 @@
|
||||
/*
|
||||
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_MotorsOcta.cpp - ArduCopter motors library |
||||
* Code by RandyMackay. DIYDrones.com |
||||
* |
||||
*/ |
||||
|
||||
#include "AP_MotorsOcta.h" |
||||
|
||||
// setup_motors - configures the motors for a octa
|
||||
void AP_MotorsOcta::setup_motors() |
||||
{ |
||||
// call parent
|
||||
AP_MotorsMatrix::setup_motors(); |
||||
|
||||
// hard coded config for supported frames
|
||||
if( _flags.frame_orientation == AP_MOTORS_PLUS_FRAME ) { |
||||
// plus frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
||||
add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
||||
add_motor(AP_MOTORS_MOT_3, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
||||
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
||||
add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); |
||||
add_motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); |
||||
add_motor(AP_MOTORS_MOT_7, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); |
||||
add_motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
||||
|
||||
}else if( _flags.frame_orientation == AP_MOTORS_V_FRAME ) { |
||||
// V frame set-up
|
||||
add_motor_raw(AP_MOTORS_MOT_1, 1.0f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); |
||||
add_motor_raw(AP_MOTORS_MOT_2, -1.0f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
||||
add_motor_raw(AP_MOTORS_MOT_3, 1.0f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); |
||||
add_motor_raw(AP_MOTORS_MOT_4, -0.5f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
||||
add_motor_raw(AP_MOTORS_MOT_5, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); |
||||
add_motor_raw(AP_MOTORS_MOT_6, -1.0f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
||||
add_motor_raw(AP_MOTORS_MOT_7, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
||||
add_motor_raw(AP_MOTORS_MOT_8, 0.5f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
||||
|
||||
}else { |
||||
// X frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
||||
add_motor(AP_MOTORS_MOT_2, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
||||
add_motor(AP_MOTORS_MOT_3, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
||||
add_motor(AP_MOTORS_MOT_4, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
||||
add_motor(AP_MOTORS_MOT_5, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); |
||||
add_motor(AP_MOTORS_MOT_6, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); |
||||
add_motor(AP_MOTORS_MOT_7, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); |
||||
add_motor(AP_MOTORS_MOT_8, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
||||
} |
||||
|
||||
// normalise factors to magnitude 0.5
|
||||
normalise_rpy_factors(); |
||||
} |
@ -1,24 +0,0 @@
@@ -1,24 +0,0 @@
|
||||
/// @file AP_MotorsOcta.h
|
||||
/// @brief Motor control class for Octacopters
|
||||
#pragma once |
||||
|
||||
#include <AP_Common/AP_Common.h> |
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library |
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library |
||||
#include "AP_MotorsMatrix.h" // Parent Motors Matrix library |
||||
|
||||
/// @class AP_MotorsOcta
|
||||
class AP_MotorsOcta : public AP_MotorsMatrix { |
||||
public: |
||||
|
||||
/// Constructor
|
||||
AP_MotorsOcta(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : |
||||
AP_MotorsMatrix(loop_rate, speed_hz) |
||||
{ }; |
||||
|
||||
// setup_motors - configures the motors for an octa
|
||||
virtual void setup_motors(); |
||||
|
||||
protected: |
||||
|
||||
}; |
@ -1,75 +0,0 @@
@@ -1,75 +0,0 @@
|
||||
/*
|
||||
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_MotorsOctaQuad.cpp - ArduCopter motors library |
||||
* Code by RandyMackay. DIYDrones.com |
||||
* |
||||
*/ |
||||
|
||||
#include "AP_MotorsOctaQuad.h" |
||||
|
||||
// setup_motors - configures the motors for a octa
|
||||
void AP_MotorsOctaQuad::setup_motors() |
||||
{ |
||||
// call parent
|
||||
AP_MotorsMatrix::setup_motors(); |
||||
|
||||
// hard coded config for supported frames
|
||||
if( _flags.frame_orientation == AP_MOTORS_PLUS_FRAME ) { |
||||
// plus frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); |
||||
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); |
||||
add_motor(AP_MOTORS_MOT_3, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); |
||||
add_motor(AP_MOTORS_MOT_4, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
||||
add_motor(AP_MOTORS_MOT_5, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); |
||||
add_motor(AP_MOTORS_MOT_6, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); |
||||
add_motor(AP_MOTORS_MOT_7, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
||||
add_motor(AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); |
||||
}else if( _flags.frame_orientation == AP_MOTORS_V_FRAME ) { |
||||
// V frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 45, 0.7981f, 1); |
||||
add_motor(AP_MOTORS_MOT_2, -45, -0.7981f, 7); |
||||
add_motor(AP_MOTORS_MOT_3, -135, 1.0000f, 5); |
||||
add_motor(AP_MOTORS_MOT_4, 135, -1.0000f, 3); |
||||
add_motor(AP_MOTORS_MOT_5, -45, 0.7981f, 8); |
||||
add_motor(AP_MOTORS_MOT_6, 45, -0.7981f, 2); |
||||
add_motor(AP_MOTORS_MOT_7, 135, 1.0000f, 4); |
||||
add_motor(AP_MOTORS_MOT_8, -135, -1.0000f, 6); |
||||
}else if( _flags.frame_orientation == AP_MOTORS_H_FRAME ) { |
||||
// H frame set-up - same as X but motors spin in opposite directions
|
||||
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
||||
add_motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7); |
||||
add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
||||
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); |
||||
add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8); |
||||
add_motor(AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
||||
add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); |
||||
add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); |
||||
}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, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); |
||||
add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); |
||||
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
||||
add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); |
||||
add_motor(AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); |
||||
add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
||||
add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); |
||||
} |
||||
|
||||
// normalise factors to magnitude 0.5
|
||||
normalise_rpy_factors(); |
||||
} |
@ -1,24 +0,0 @@
@@ -1,24 +0,0 @@
|
||||
/// @file AP_MotorsOctaQuad.h
|
||||
/// @brief Motor control class for OctaQuadcopters
|
||||
#pragma once |
||||
|
||||
#include <AP_Common/AP_Common.h> |
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library |
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library |
||||
#include "AP_MotorsMatrix.h" // Parent Motors Matrix library |
||||
|
||||
/// @class AP_MotorsOcta
|
||||
class AP_MotorsOctaQuad : public AP_MotorsMatrix { |
||||
public: |
||||
|
||||
/// Constructor
|
||||
AP_MotorsOctaQuad(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : |
||||
AP_MotorsMatrix(loop_rate, speed_hz) |
||||
{ }; |
||||
|
||||
// setup_motors - configures the motors for a quad
|
||||
virtual void setup_motors(); |
||||
|
||||
protected: |
||||
|
||||
}; |
@ -1,106 +0,0 @@
@@ -1,106 +0,0 @@
|
||||
/*
|
||||
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( _flags.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( _flags.frame_orientation == AP_MOTORS_V_FRAME ) { |
||||
// V frame set-up
|
||||
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); |
||||
|
||||
}else if( _flags.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 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 |
||||
|
||||
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. |
||||
|
||||
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)) |
||||
*/ |
||||
|
||||
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 |
||||
|
||||
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 |
||||
|
||||
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); |
||||
} 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); |
||||
}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); |
||||
} |
||||
|
||||
// normalise factors to magnitude 0.5
|
||||
normalise_rpy_factors(); |
||||
} |
@ -1,24 +0,0 @@
@@ -1,24 +0,0 @@
|
||||
/// @file AP_MotorsQuad.h
|
||||
/// @brief Motor control class for Quadcopters
|
||||
#pragma once |
||||
|
||||
#include <AP_Common/AP_Common.h> |
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library |
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library |
||||
#include "AP_MotorsMatrix.h" // Parent Motors Matrix library |
||||
|
||||
/// @class AP_MotorsQuad
|
||||
class AP_MotorsQuad : public AP_MotorsMatrix { |
||||
public: |
||||
|
||||
/// Constructor
|
||||
AP_MotorsQuad(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : |
||||
AP_MotorsMatrix(loop_rate, speed_hz) |
||||
{ }; |
||||
|
||||
// setup_motors - configures the motors for a quad
|
||||
virtual void setup_motors(); |
||||
|
||||
protected: |
||||
|
||||
}; |
@ -1,50 +0,0 @@
@@ -1,50 +0,0 @@
|
||||
/*
|
||||
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_MotorsY6.cpp - ArduCopter motors library |
||||
* Code by RandyMackay. DIYDrones.com |
||||
* |
||||
*/ |
||||
|
||||
#include "AP_MotorsY6.h" |
||||
|
||||
// setup_motors - configures the motors for a hexa
|
||||
void AP_MotorsY6::setup_motors() |
||||
{ |
||||
// call parent
|
||||
AP_MotorsMatrix::setup_motors(); |
||||
|
||||
if (_flags.frame_orientation >= AP_MOTORS_NEW_PLUS_FRAME) { |
||||
// Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise
|
||||
add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
||||
add_motor_raw(AP_MOTORS_MOT_2, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
||||
add_motor_raw(AP_MOTORS_MOT_3, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
||||
add_motor_raw(AP_MOTORS_MOT_4, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
||||
add_motor_raw(AP_MOTORS_MOT_5, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
||||
add_motor_raw(AP_MOTORS_MOT_6, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); |
||||
}else{ |
||||
// original Y6 motor definition
|
||||
add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
||||
add_motor_raw(AP_MOTORS_MOT_2, 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
||||
add_motor_raw(AP_MOTORS_MOT_3, 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); |
||||
add_motor_raw(AP_MOTORS_MOT_4, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); |
||||
add_motor_raw(AP_MOTORS_MOT_5, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
||||
add_motor_raw(AP_MOTORS_MOT_6, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); |
||||
} |
||||
|
||||
// normalise factors to magnitude 0.5
|
||||
normalise_rpy_factors(); |
||||
} |
@ -1,26 +0,0 @@
@@ -1,26 +0,0 @@
|
||||
/// @file AP_MotorsY6.h
|
||||
/// @brief Motor control class for Y6 frames
|
||||
#pragma once |
||||
|
||||
#include <AP_Common/AP_Common.h> |
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library |
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library |
||||
#include "AP_MotorsMatrix.h" // Parent Motors Matrix library |
||||
|
||||
#define AP_MOTORS_Y6_YAW_DIRECTION 1 // this really should be a user selectable parameter
|
||||
|
||||
/// @class AP_MotorsY6
|
||||
class AP_MotorsY6 : public AP_MotorsMatrix { |
||||
public: |
||||
|
||||
/// Constructor
|
||||
AP_MotorsY6(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : |
||||
AP_MotorsMatrix(loop_rate, speed_hz) |
||||
{ }; |
||||
|
||||
// setup_motors - configures the motors for a Y6
|
||||
virtual void setup_motors(); |
||||
|
||||
protected: |
||||
|
||||
}; |
Loading…
Reference in new issue