2010-12-19 12:40:33 -04:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
|
|
|
2011-02-24 01:56:59 -04:00
|
|
|
|
|
|
|
// ACM:
|
|
|
|
// Motors
|
|
|
|
#define RIGHT CH_1
|
|
|
|
#define LEFT CH_2
|
|
|
|
#define FRONT CH_3
|
|
|
|
#define BACK CH_4
|
|
|
|
#define RIGHTFRONT CH_7
|
|
|
|
#define LEFTBACK CH_8
|
|
|
|
#define MAX_SERVO_OUTPUT 2700
|
|
|
|
|
|
|
|
// active altitude sensor
|
|
|
|
#define SONAR 0
|
|
|
|
#define BARO 1
|
|
|
|
|
|
|
|
// Frame types
|
|
|
|
#define PLUS_FRAME 0
|
|
|
|
#define X_FRAME 1
|
|
|
|
#define TRI_FRAME 2
|
|
|
|
#define HEXA_FRAME 3
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
// Internal defines, don't edit and expect things to work
|
|
|
|
// -------------------------------------------------------
|
|
|
|
|
2011-02-19 03:44:44 -04:00
|
|
|
#define TRUE 1
|
|
|
|
#define FALSE 0
|
|
|
|
#define ToRad(x) (x*0.01745329252) // *pi/180
|
|
|
|
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
#define DEBUG 0
|
|
|
|
#define LOITER_RANGE 30 // for calculating power outside of loiter radius
|
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
#define T6 1000000
|
|
|
|
#define T7 10000000
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
// GPS type codes - use the names, not the numbers
|
|
|
|
#define GPS_PROTOCOL_NONE -1
|
|
|
|
#define GPS_PROTOCOL_NMEA 0
|
|
|
|
#define GPS_PROTOCOL_SIRF 1
|
|
|
|
#define GPS_PROTOCOL_UBLOX 2
|
|
|
|
#define GPS_PROTOCOL_IMU 3
|
|
|
|
#define GPS_PROTOCOL_MTK 4
|
2011-02-19 03:44:44 -04:00
|
|
|
#define GPS_PROTOCOL_HIL 5
|
|
|
|
#define GPS_PROTOCOL_MTK16 6
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
// Radio channels
|
2011-02-17 05:36:33 -04:00
|
|
|
// Note channels are from 0!
|
2010-12-19 12:40:33 -04:00
|
|
|
//
|
|
|
|
// XXX these should be CH_n defines from RC.h at some point.
|
|
|
|
#define CH_1 0
|
|
|
|
#define CH_2 1
|
|
|
|
#define CH_3 2
|
|
|
|
#define CH_4 3
|
|
|
|
#define CH_5 4
|
|
|
|
#define CH_6 5
|
|
|
|
#define CH_7 6
|
|
|
|
#define CH_8 7
|
|
|
|
|
|
|
|
#define CH_ROLL CH_1
|
|
|
|
#define CH_PITCH CH_2
|
|
|
|
#define CH_THROTTLE CH_3
|
|
|
|
#define CH_RUDDER CH_4
|
|
|
|
#define CH_YAW CH_4
|
|
|
|
|
2011-02-19 03:44:44 -04:00
|
|
|
// HIL enumerations
|
|
|
|
#define HIL_PROTOCOL_XPLANE 1
|
|
|
|
#define HIL_PROTOCOL_MAVLINK 2
|
|
|
|
|
|
|
|
#define HIL_MODE_DISABLED 0
|
|
|
|
#define HIL_MODE_ATTITUDE 1
|
|
|
|
#define HIL_MODE_SENSORS 2
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
// GCS enumeration
|
2011-02-24 01:56:59 -04:00
|
|
|
#define GCS_PROTOCOL_STANDARD 0 // standard APM protocol
|
|
|
|
#define GCS_PROTOCOL_LEGACY 1 // legacy ArduPilot protocol
|
|
|
|
#define GCS_PROTOCOL_XPLANE 2 // X-Plane HIL simulation
|
|
|
|
#define GCS_PROTOCOL_DEBUGTERMINAL 3 //Human-readable debug interface for use with a dumb terminal
|
|
|
|
#define GCS_PROTOCOL_MAVLINK 4 // binary protocol for qgroundcontrol
|
|
|
|
#define GCS_PROTOCOL_NONE -1 // No GCS output
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
// Auto Pilot modes
|
|
|
|
// ----------------
|
2011-02-19 22:03:01 -04:00
|
|
|
#define STABILIZE 0 // hold level position
|
|
|
|
#define ACRO 1 // rate control
|
|
|
|
#define ALT_HOLD 2 // AUTO control
|
2010-12-26 15:49:11 -04:00
|
|
|
#define FBW 3 // AUTO control
|
|
|
|
#define AUTO 4 // AUTO control
|
2011-03-02 22:32:50 -04:00
|
|
|
#define GCS_AUTO 5 // AUTO control
|
2011-03-09 02:37:09 -04:00
|
|
|
#define LOITER 6 // Hold a single location
|
2011-02-24 01:56:59 -04:00
|
|
|
#define RTL 7 // AUTO control
|
2011-03-09 02:37:09 -04:00
|
|
|
#define NUM_MODES 8
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-03-05 00:56:58 -04:00
|
|
|
|
|
|
|
#define WP_OPT_ALT_RELATIVE (1<<0)
|
|
|
|
#define WP_OPT_ALT_CHANGE (1<<1)
|
|
|
|
#define WP_OPT_YAW (1<<2)
|
|
|
|
// ..
|
|
|
|
#define WP_OPT_CMD_WAIT (1<<7)
|
|
|
|
|
|
|
|
|
|
|
|
// Commands - Note that APM (1<<9)now uses a subset of the MAVLink protocol commands. See enum MAV_CMD in the GCS_Mavlink library
|
2011-03-02 22:32:50 -04:00
|
|
|
#define CMD_BLANK 0 // there is no command stored in the mem location requested
|
|
|
|
#define NO_COMMAND 0
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//repeating events
|
|
|
|
#define NO_REPEAT 0
|
|
|
|
#define CH_4_TOGGLE 1
|
|
|
|
#define CH_5_TOGGLE 2
|
|
|
|
#define CH_6_TOGGLE 3
|
|
|
|
#define CH_7_TOGGLE 4
|
|
|
|
#define RELAY_TOGGLE 5
|
|
|
|
#define STOP_REPEAT 10
|
|
|
|
|
2011-03-10 22:49:12 -04:00
|
|
|
#define MAV_CMD_CONDITION_YAW 23
|
2011-02-19 17:02:27 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
// GCS Message ID's
|
|
|
|
#define MSG_ACKNOWLEDGE 0x00
|
|
|
|
#define MSG_HEARTBEAT 0x01
|
|
|
|
#define MSG_ATTITUDE 0x02
|
|
|
|
#define MSG_LOCATION 0x03
|
|
|
|
#define MSG_PRESSURE 0x04
|
|
|
|
#define MSG_STATUS_TEXT 0x05
|
|
|
|
#define MSG_PERF_REPORT 0x06
|
2011-02-18 23:59:58 -04:00
|
|
|
#define MSG_MODE_CHANGE 0x07 //This is different than HEARTBEAT because it occurs only when the mode is actually changed
|
|
|
|
#define MSG_VERSION_REQUEST 0x08
|
|
|
|
#define MSG_VERSION 0x09
|
|
|
|
#define MSG_EXTENDED_STATUS 0x0a
|
|
|
|
#define MSG_CPU_LOAD 0x0b
|
|
|
|
|
|
|
|
#define MSG_COMMAND_REQUEST 0x20
|
|
|
|
#define MSG_COMMAND_UPLOAD 0x21
|
|
|
|
#define MSG_COMMAND_LIST 0x22
|
|
|
|
#define MSG_COMMAND_MODE_CHANGE 0x23
|
|
|
|
#define MSG_CURRENT_WAYPOINT 0x24
|
|
|
|
|
|
|
|
#define MSG_VALUE_REQUEST 0x30
|
|
|
|
#define MSG_VALUE_SET 0x31
|
2010-12-19 12:40:33 -04:00
|
|
|
#define MSG_VALUE 0x32
|
2011-02-18 23:59:58 -04:00
|
|
|
|
|
|
|
#define MSG_PID_REQUEST 0x40
|
|
|
|
#define MSG_PID_SET 0x41
|
2010-12-19 12:40:33 -04:00
|
|
|
#define MSG_PID 0x42
|
2011-02-18 23:59:58 -04:00
|
|
|
#define MSG_VFR_HUD 0x4a
|
|
|
|
|
|
|
|
#define MSG_TRIM_STARTUP 0x50
|
|
|
|
#define MSG_TRIM_MIN 0x51
|
|
|
|
#define MSG_TRIM_MAX 0x52
|
|
|
|
#define MSG_RADIO_OUT 0x53
|
|
|
|
#define MSG_RADIO_IN 0x54
|
|
|
|
|
|
|
|
#define MSG_RAW_IMU 0x60
|
|
|
|
#define MSG_GPS_STATUS 0x61
|
|
|
|
#define MSG_GPS_RAW 0x62
|
|
|
|
|
|
|
|
#define MSG_SERVO_OUT 0x70
|
|
|
|
|
|
|
|
#define MSG_PIN_REQUEST 0x80
|
|
|
|
#define MSG_PIN_SET 0x81
|
|
|
|
|
|
|
|
#define MSG_DATAFLASH_REQUEST 0x90
|
|
|
|
#define MSG_DATAFLASH_SET 0x91
|
|
|
|
|
|
|
|
#define MSG_EEPROM_REQUEST 0xa0
|
|
|
|
#define MSG_EEPROM_SET 0xa1
|
|
|
|
|
|
|
|
#define MSG_POSITION_CORRECT 0xb0
|
|
|
|
#define MSG_ATTITUDE_CORRECT 0xb1
|
|
|
|
#define MSG_POSITION_SET 0xb2
|
|
|
|
#define MSG_ATTITUDE_SET 0xb3
|
|
|
|
#define MSG_LOCAL_LOCATION 0xb4
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
#define SEVERITY_LOW 1
|
|
|
|
#define SEVERITY_MEDIUM 2
|
|
|
|
#define SEVERITY_HIGH 3
|
|
|
|
#define SEVERITY_CRITICAL 4
|
|
|
|
|
|
|
|
// Logging parameters
|
2011-02-19 03:44:44 -04:00
|
|
|
#define LOG_INDEX_MSG 0xF0
|
2010-12-19 12:40:33 -04:00
|
|
|
#define LOG_ATTITUDE_MSG 0x01
|
|
|
|
#define LOG_GPS_MSG 0x02
|
|
|
|
#define LOG_MODE_MSG 0X03
|
|
|
|
#define LOG_CONTROL_TUNING_MSG 0X04
|
|
|
|
#define LOG_NAV_TUNING_MSG 0X05
|
|
|
|
#define LOG_PERFORMANCE_MSG 0X06
|
|
|
|
#define LOG_RAW_MSG 0x07
|
|
|
|
#define LOG_CMD_MSG 0x08
|
2011-01-16 23:44:12 -04:00
|
|
|
#define LOG_CURRENT_MSG 0x09
|
|
|
|
#define LOG_STARTUP_MSG 0x0A
|
2010-12-19 12:40:33 -04:00
|
|
|
#define TYPE_AIRSTART_MSG 0x00
|
|
|
|
#define TYPE_GROUNDSTART_MSG 0x01
|
2011-02-19 03:44:44 -04:00
|
|
|
#define MAX_NUM_LOGS 50
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-01-16 23:44:12 -04:00
|
|
|
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
|
|
|
#define MASK_LOG_ATTITUDE_MED (1<<1)
|
|
|
|
#define MASK_LOG_GPS (1<<2)
|
|
|
|
#define MASK_LOG_PM (1<<3)
|
|
|
|
#define MASK_LOG_CTUN (1<<4)
|
|
|
|
#define MASK_LOG_NTUN (1<<5)
|
|
|
|
#define MASK_LOG_MODE (1<<6)
|
|
|
|
#define MASK_LOG_RAW (1<<7)
|
|
|
|
#define MASK_LOG_CMD (1<<8)
|
|
|
|
#define MASK_LOG_CUR (1<<9)
|
2011-03-11 17:37:37 -04:00
|
|
|
#define MASK_LOG_SET_DEFAULTS (1<<15)
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
// Waypoint Modes
|
|
|
|
// ----------------
|
|
|
|
#define ABS_WP 0
|
|
|
|
#define REL_WP 1
|
|
|
|
|
|
|
|
// Command Queues
|
|
|
|
// ---------------
|
|
|
|
#define COMMAND_MUST 0
|
2011-02-17 05:36:33 -04:00
|
|
|
#define COMMAND_MAY 1
|
|
|
|
#define COMMAND_NOW 2
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
// Events
|
|
|
|
// ------
|
|
|
|
#define EVENT_WILL_REACH_WAYPOINT 1
|
|
|
|
#define EVENT_SET_NEW_WAYPOINT_INDEX 2
|
|
|
|
#define EVENT_LOADED_WAYPOINT 3
|
|
|
|
#define EVENT_LOOP 4
|
|
|
|
|
2011-02-24 01:56:59 -04:00
|
|
|
// Climb rate calculations
|
|
|
|
#define ALTITUDE_HISTORY_LENGTH 8 //Number of (time,altitude) points to regress a climb rate from
|
|
|
|
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO
|
|
|
|
|
2011-01-16 23:44:12 -04:00
|
|
|
#define CURRENT_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*CURR_VOLT_DIV_RATIO
|
|
|
|
#define CURRENT_AMPS(x) (x*(INPUT_VOLTAGE/1024.0))*CURR_AMP_DIV_RATIO
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
#define AIRSPEED_CH 7 // The external ADC channel for the airspeed sensor
|
|
|
|
#define BATTERY_PIN1 0 // These are the pins for the voltage dividers
|
|
|
|
#define BATTERY_PIN2 1
|
|
|
|
#define BATTERY_PIN3 2
|
|
|
|
#define BATTERY_PIN4 3
|
2011-01-17 22:48:44 -04:00
|
|
|
|
|
|
|
#define VOLTAGE_PIN_0 0 // These are the pins for current sensor: voltage
|
|
|
|
#define CURRENT_PIN_1 1 // and current
|
2011-01-16 23:44:12 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
#define RELAY_PIN 47
|
|
|
|
|
2011-01-16 23:44:12 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
// sonar
|
|
|
|
#define SonarToCm(x) (x*1.26) // Sonar raw value to centimeters
|
|
|
|
|
|
|
|
// Hardware Parameters
|
|
|
|
#define SLIDE_SWITCH_PIN 40
|
|
|
|
#define PUSHBUTTON_PIN 41
|
|
|
|
|
|
|
|
#define A_LED_PIN 37 //36 = B, 37 = A, 35 = C
|
|
|
|
#define B_LED_PIN 36
|
|
|
|
#define C_LED_PIN 35
|
|
|
|
|
|
|
|
|
|
|
|
// EEPROM addresses
|
|
|
|
#define EEPROM_MAX_ADDR 4096
|
2011-02-24 01:56:59 -04:00
|
|
|
// parameters get the first 1KiB of EEPROM, remainder is for waypoints
|
|
|
|
#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP
|
2011-03-05 16:50:49 -04:00
|
|
|
#define WP_SIZE 15
|