Arducopter Frames: revert to old HEXA_FRAME and OCTA_FRAME defines.

* HEXA_X_FRAME and HEXA_PLUS_FRAME merged back into HEXA_FRAME
* OCTA_V_FRAME merged back into OCTA_FRAME
This commit is contained in:
Pat Hickey 2012-01-25 22:22:28 -08:00
parent 0e9294538b
commit b245265669
2 changed files with 2 additions and 24 deletions

View File

@ -56,8 +56,7 @@
# define MOT_6 CH_INVALID
# define MOT_7 CH_INVALID
# define MOT_8 CH_INVALID
#elif FRAME_CONFIG == HEXA_X_FRAME
// X orientation (what will be the best way to set 'if' 'else'? )
#elif FRAME_CONFIG == HEXA_FRAME
# define MOT_1 CH_7
# define MOT_2 CH_3
# define MOT_3 CH_2
@ -67,16 +66,6 @@
// Placeholders:
# define MOT_7 CH_INVALID
# define MOT_8 CH_INVALID
#elif FRAME_CONFIG == HEXA_PLUS_FRAME
# define MOT_1 CH_4
# define MOT_2 CH_1
# define MOT_3 CH_7
# define MOT_4 CH_3
# define MOT_5 CH_2
# define MOT_6 CH_8
// Placeholders:
# define MOT_7 CH_INVALID
# define MOT_8 CH_INVALID
#elif FRAME_CONFIG == Y6_FRAME
# define MOT_1 CH_1
# define MOT_2 CH_7
@ -96,15 +85,6 @@
# define MOT_6 CH_7
# define MOT_7 CH_4
# define MOT_8 CH_3
#elif FRAME_CONFIG == OCTA_V_FRAME
# define MOT_1 CH_4
# define MOT_2 CH_2
# define MOT_3 CH_8
# define MOT_4 CH_10
# define MOT_5 CH_7
# define MOT_6 CH_1
# define MOT_7 CH_3
# define MOT_8 CH_11
#elif FRAME_CONFIG == OCTA_QUAD_FRAME
# define MOT_1 CH_1
# define MOT_2 CH_2

View File

@ -46,13 +46,11 @@
// Frame types
#define QUAD_FRAME 0
#define TRI_FRAME 1
#define HEXA_X_FRAME 2
#define HEXA_FRAME 2
#define Y6_FRAME 3
#define OCTA_FRAME 4
#define HELI_FRAME 5
#define OCTA_QUAD_FRAME 6
#define HEXA_PLUS_FRAME 7
#define OCTA_V_FRAME 8
#define PLUS_FRAME 0
#define X_FRAME 1