31 if (autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
32 switch (vehicleType) {
33 case MAV_TYPE_QUADROTOR:
34 case MAV_TYPE_HEXAROTOR:
35 case MAV_TYPE_OCTOROTOR:
36 case MAV_TYPE_TRICOPTER:
37 case MAV_TYPE_COAXIAL:
38 case MAV_TYPE_HELICOPTER:
39 if (!_arduCopterPluginInstance) {
42 return _arduCopterPluginInstance;
43 case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
44 case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
45 case MAV_TYPE_VTOL_TILTROTOR:
46 case MAV_TYPE_VTOL_FIXEDROTOR:
47 case MAV_TYPE_VTOL_TAILSITTER:
48 case MAV_TYPE_VTOL_TILTWING:
49 case MAV_TYPE_VTOL_RESERVED5:
50 case MAV_TYPE_FIXED_WING:
51 if (!_arduPlanePluginInstance) {
54 return _arduPlanePluginInstance;
55 case MAV_TYPE_GROUND_ROVER:
56 case MAV_TYPE_SURFACE_BOAT:
57 if (!_arduRoverPluginInstance) {
60 return _arduRoverPluginInstance;
61 case MAV_TYPE_SUBMARINE:
62 if (!_arduSubPluginInstance) {
65 return _arduSubPluginInstance;