Copter: moved MAV_TYPE to Copter.h

This commit is contained in:
floaledm 2016-08-23 14:16:04 -05:00 committed by Andrew Tridgell
parent 96de005591
commit 893614897e
2 changed files with 17 additions and 17 deletions

View File

@ -314,6 +314,23 @@ private:
uint8_t compass : 1; // true if compass is healthy
} sensor_health;
// setup FRAME_MAV_TYPE
#if (FRAME_CONFIG == QUAD_FRAME)
#define FRAME_MAV_TYPE MAV_TYPE_QUADROTOR
#elif (FRAME_CONFIG == TRI_FRAME)
#define FRAME_MAV_TYPE MAV_TYPE_TRICOPTER
#elif (FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME)
#define FRAME_MAV_TYPE MAV_TYPE_HEXAROTOR
#elif (FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME)
#define FRAME_MAV_TYPE MAV_TYPE_OCTOROTOR
#elif (FRAME_CONFIG == HELI_FRAME)
#define FRAME_MAV_TYPE MAV_TYPE_HELICOPTER
#elif (FRAME_CONFIG == SINGLE_FRAME || FRAME_CONFIG == COAX_FRAME) //because mavlink did not define a singlecopter, we use a quad
#define FRAME_MAV_TYPE MAV_TYPE_QUADROTOR
#else
#error Unrecognised frame type
#endif
// Motor Output
#if FRAME_CONFIG == QUAD_FRAME
#define MOTOR_CLASS AP_MotorsQuad

View File

@ -480,20 +480,3 @@ enum LandStateType {
#define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0)
#define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1)
#define THR_BEHAVE_DISARM_ON_LAND_DETECT (1<<2)
// setup FRAME_MAV_TYPE
#if (FRAME_CONFIG == QUAD_FRAME)
# define FRAME_MAV_TYPE MAV_TYPE_QUADROTOR
#elif (FRAME_CONFIG == TRI_FRAME)
# define FRAME_MAV_TYPE MAV_TYPE_TRICOPTER
#elif (FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME)
# define FRAME_MAV_TYPE MAV_TYPE_HEXAROTOR
#elif (FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME)
# define FRAME_MAV_TYPE MAV_TYPE_OCTOROTOR
#elif (FRAME_CONFIG == HELI_FRAME)
# define FRAME_MAV_TYPE MAV_TYPE_HELICOPTER
#elif (FRAME_CONFIG == SINGLE_FRAME || FRAME_CONFIG == COAX_FRAME) //because mavlink did not define a singlecopter, we use a quad
# define FRAME_MAV_TYPE MAV_TYPE_QUADROTOR
#else
#error Unrecognised frame type
#endif