Subversion Repositories Projects

Rev

Go to most recent revision | Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
using System;
2
using System.Collections.Generic;
3
using System.Linq;
4
using System.Text;
5
 
6
namespace ArdupilotMega
7
{
8
    public partial class MAVLink
9
    {
10
 
11
#if !MAVLINK10
12
        enum MAV_CLASS
13
        {
14
            MAV_CLASS_GENERIC = 0,        /// Generic autopilot, full support for everything
15
            MAV_CLASS_PIXHAWK = 1,        /// PIXHAWK autopilot, http://pixhawk.ethz.ch
16
            MAV_CLASS_SLUGS = 2,          /// SLUGS autopilot, http://slugsuav.soe.ucsc.edu
17
            MAV_CLASS_ARDUPILOTMEGA = 3,  /// ArduPilotMega / ArduCopter, http://diydrones.com
18
            MAV_CLASS_OPENPILOT = 4,      /// OpenPilot, http://openpilot.org
19
            MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5,  /// Generic autopilot only supporting simple waypoints
20
            MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, /// Generic autopilot supporting waypoints and other simple navigation commands
21
            MAV_CLASS_GENERIC_MISSION_FULL = 7,            /// Generic autopilot supporting the full mission command set
22
            MAV_CLASS_NONE = 8,           /// No valid autopilot
23
            MAV_CLASS_NB                  /// Number of autopilot classes
24
        };
25
 
26
        public enum MAV_ACTION
27
        {
28
            MAV_ACTION_HOLD = 0,
29
            MAV_ACTION_MOTORS_START = 1,
30
            MAV_ACTION_LAUNCH = 2,
31
            MAV_ACTION_RETURN = 3,
32
            MAV_ACTION_EMCY_LAND = 4,
33
            MAV_ACTION_EMCY_KILL = 5,
34
            MAV_ACTION_CONFIRM_KILL = 6,
35
            MAV_ACTION_CONTINUE = 7,
36
            MAV_ACTION_MOTORS_STOP = 8,
37
            MAV_ACTION_HALT = 9,
38
            MAV_ACTION_SHUTDOWN = 10,
39
            MAV_ACTION_REBOOT = 11,
40
            MAV_ACTION_SET_MANUAL = 12,
41
            MAV_ACTION_SET_AUTO = 13,
42
            MAV_ACTION_STORAGE_READ = 14,
43
            MAV_ACTION_STORAGE_WRITE = 15,
44
            MAV_ACTION_CALIBRATE_RC = 16,
45
            MAV_ACTION_CALIBRATE_GYRO = 17,
46
            MAV_ACTION_CALIBRATE_MAG = 18,
47
            MAV_ACTION_CALIBRATE_ACC = 19,
48
            MAV_ACTION_CALIBRATE_PRESSURE = 20,
49
            MAV_ACTION_REC_START = 21,
50
            MAV_ACTION_REC_PAUSE = 22,
51
            MAV_ACTION_REC_STOP = 23,
52
            MAV_ACTION_TAKEOFF = 24,
53
            MAV_ACTION_NAVIGATE = 25,
54
            MAV_ACTION_LAND = 26,
55
            MAV_ACTION_LOITER = 27,
56
            MAV_ACTION_SET_ORIGIN = 28,
57
            MAV_ACTION_RELAY_ON = 29,
58
            MAV_ACTION_RELAY_OFF = 30,
59
            MAV_ACTION_GET_IMAGE = 31,
60
            MAV_ACTION_VIDEO_START = 32,
61
            MAV_ACTION_VIDEO_STOP = 33,
62
            MAV_ACTION_RESET_MAP = 34,
63
            MAV_ACTION_RESET_PLAN = 35,
64
            MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
65
            MAV_ACTION_ASCEND_AT_RATE = 37,
66
            MAV_ACTION_CHANGE_MODE = 38,
67
            MAV_ACTION_LOITER_MAX_TURNS = 39,
68
            MAV_ACTION_LOITER_MAX_TIME = 40,
69
            MAV_ACTION_START_HILSIM = 41,
70
            MAV_ACTION_STOP_HILSIM = 42,
71
            MAV_ACTION_NB        /// Number of MAV actions
72
        };
73
 
74
        public enum MAV_MODE
75
        {
76
            MAV_MODE_UNINIT = 0,     /// System is in undefined state
77
            MAV_MODE_LOCKED = 1,     /// Motors are blocked, system is safe
78
            MAV_MODE_MANUAL = 2,     /// System is allowed to be active, under manual (RC) control
79
            MAV_MODE_GUIDED = 3,     /// System is allowed to be active, under autonomous control, manual setpoint
80
            MAV_MODE_AUTO = 4,     /// System is allowed to be active, under autonomous control and navigation
81
            MAV_MODE_TEST1 = 5,     /// Generic test mode, for custom use
82
            MAV_MODE_TEST2 = 6,     /// Generic test mode, for custom use
83
            MAV_MODE_TEST3 = 7,     /// Generic test mode, for custom use
84
            MAV_MODE_READY = 8,     /// System is ready, motors are unblocked, but controllers are inactive
85
            MAV_MODE_RC_TRAINING = 9 /// System is blocked, only RC valued are read and reported back
86
        };
87
 
88
        public enum MAV_STATE
89
        {
90
            MAV_STATE_UNINIT = 0,
91
            MAV_STATE_BOOT,
92
            MAV_STATE_CALIBRATING,
93
            MAV_STATE_STANDBY,
94
            MAV_STATE_ACTIVE,
95
            MAV_STATE_CRITICAL,
96
            MAV_STATE_EMERGENCY,
97
            MAV_STATE_HILSIM,
98
            MAV_STATE_POWEROFF
99
        };
100
 
101
        public enum MAV_NAV
102
        {
103
            MAV_NAV_GROUNDED = 0,
104
            MAV_NAV_LIFTOFF,
105
            MAV_NAV_HOLD,
106
            MAV_NAV_WAYPOINT,
107
            MAV_NAV_VECTOR,
108
            MAV_NAV_RETURNING,
109
            MAV_NAV_LANDING,
110
            MAV_NAV_LOST,
111
            MAV_NAV_LOITER,
112
            MAV_NAV_FREE_DRIFT
113
        };
114
 
115
        public enum MAV_TYPE
116
        {
117
            MAV_GENERIC = 0,
118
            MAV_FIXED_WING = 1,
119
            MAV_QUADROTOR = 2,
120
            MAV_COAXIAL = 3,
121
            MAV_HELICOPTER = 4,
122
            MAV_GROUND = 5,
123
            OCU = 6,
124
            MAV_AIRSHIP = 7,
125
            MAV_FREE_BALLOON = 8,
126
            MAV_ROCKET = 9,
127
            UGV_GROUND_ROVER = 10,
128
            UGV_SURFACE_SHIP = 11
129
        };
130
 
131
        public enum MAV_AUTOPILOT_TYPE
132
        {
133
            MAV_AUTOPILOT_GENERIC = 0,
134
            MAV_AUTOPILOT_PIXHAWK = 1,
135
            MAV_AUTOPILOT_SLUGS = 2,
136
            MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
137
            MAV_AUTOPILOT_NONE = 4
138
        };
139
 
140
        public enum MAV_COMPONENT
141
        {
142
            MAV_COMP_ID_GPS,
143
            MAV_COMP_ID_WAYPOINTPLANNER,
144
            MAV_COMP_ID_BLOBTRACKER,
145
            MAV_COMP_ID_PATHPLANNER,
146
            MAV_COMP_ID_AIRSLAM,
147
            MAV_COMP_ID_MAPPER,
148
            MAV_COMP_ID_CAMERA,
149
            MAV_COMP_ID_IMU = 200,
150
            MAV_COMP_ID_IMU_2 = 201,
151
            MAV_COMP_ID_IMU_3 = 202,
152
            MAV_COMP_ID_UDP_BRIDGE = 240,
153
            MAV_COMP_ID_UART_BRIDGE = 241,
154
            MAV_COMP_ID_SYSTEM_CONTROL = 250
155
        };
156
 
157
        public enum MAV_FRAME
158
        {
159
            GLOBAL = 0,
160
            LOCAL = 1,
161
            MISSION = 2,
162
            GLOBAL_RELATIVE_ALT = 3,
163
            LOCAL_ENU = 4
164
        };
165
#endif
166
    }
167
}