#define LOITER_RANGE 60 // for calculating power outside of loiter radius
#define SERVO_MAX 4500 // This value represents 45 degrees and is just an arbitrary representation of servo max travel.
#define SERVO_MAX 4500 // This value represents 45 degrees and is just an
// arbitrary representation of servo max travel.
// failsafe
// ----------------------
#define FAILSAFE_NONE0
#define FAILSAFE_SHORT1
#define FAILSAFE_LONG2
#define FAILSAFE_GCS3
#defineFAILSAFE_SHORT_TIME 1500// Miliiseconds
#defineFAILSAFE_LONG_TIME 20000// Miliiseconds
#define FAILSAFE_NONE0
#define FAILSAFE_SHORT1
#define FAILSAFE_LONG2
#define FAILSAFE_GCS3
#defineFAILSAFE_SHORT_TIME 1500// Miliiseconds
#defineFAILSAFE_LONG_TIME 20000// Miliiseconds
// active altitude sensor
...
...
@@ -37,15 +38,15 @@
#define T7 10000000
// GPS type codes - use the names, not the numbers
#define GPS_PROTOCOL_NONE-1
#define GPS_PROTOCOL_NMEA0
#define GPS_PROTOCOL_SIRF1
#define GPS_PROTOCOL_UBLOX2
#define GPS_PROTOCOL_IMU3
#define GPS_PROTOCOL_MTK4
#define GPS_PROTOCOL_HIL5
#define GPS_PROTOCOL_MTK166
#define GPS_PROTOCOL_AUTO7
#define GPS_PROTOCOL_NONE-1
#define GPS_PROTOCOL_NMEA0
#define GPS_PROTOCOL_SIRF1
#define GPS_PROTOCOL_UBLOX2
#define GPS_PROTOCOL_IMU3
#define GPS_PROTOCOL_MTK4
#define GPS_PROTOCOL_HIL5
#define GPS_PROTOCOL_MTK166
#define GPS_PROTOCOL_AUTO7
#define CH_ROLL CH_1
#define CH_PITCH CH_2
...
...
@@ -54,37 +55,52 @@
#define CH_YAW CH_4
// HIL enumerations
#define HIL_MODE_DISABLED0
#define HIL_MODE_ATTITUDE1
#define HIL_MODE_SENSORS2
#define HIL_MODE_DISABLED0
#define HIL_MODE_ATTITUDE1
#define HIL_MODE_SENSORS2
// Auto Pilot modes
// ----------------
#define MANUAL 0
#define CIRCLE 1 // When flying sans GPS, and we loose the radio, just circle
#define CIRCLE 1 // When flying sans GPS, and we loose
// the radio, just circle
#define STABILIZE 2
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical = manual throttle
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical => desired airspeed
#define FLY_BY_WIRE_C 7 // Fly By Wire C has left stick horizontal => desired roll angle, left stick vertical => desired climb rate, right stick vertical => desired airspeed
// Fly By Wire B and Fly By Wire C require airspeed sensor
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal =>
// desired roll angle, left stick vertical =>
// desired pitch angle, right stick vertical =
// manual throttle
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal =>
// desired roll angle, left stick vertical =>
// desired pitch angle, right stick vertical
// => desired airspeed
#define FLY_BY_WIRE_C 7 // Fly By Wire C has left stick horizontal =>
// desired roll angle, left stick vertical =>
// desired climb rate, right stick vertical =>
// desired airspeed
// Fly By Wire B and Fly By Wire C require airspeed sensor
#define AUTO 10
#define RTL 11
#define LOITER 12
//#define TAKEOFF 13 // This is not used by APM. It appears here for consistency with ACM
//#define LAND 14 // This is not used by APM. It appears here for consistency with ACM
//#define TAKEOFF 13 // This is not used by APM. It appears here
// for consistency with ACM
//#define LAND 14 // This is not used by APM. It appears here for
// consistency with ACM
#define GUIDED 15
#define INITIALISING 16 // in startup routines
// Commands - Note that APM now uses a subset of the MAVLink protocol commands. See enum MAV_CMD in the GCS_Mavlink library
#define CMD_BLANK 0 // there is no command stored in the mem location requested
// Commands - Note that APM now uses a subset of the MAVLink protocol
// commands. See enum MAV_CMD in the GCS_Mavlink library
#define CMD_BLANK 0 // there is no command stored in the mem location