Пример #1
0
        /// <summary>
        /// Gets the parameter meta data.
        /// </summary>
        /// <param name="nodeKey">The node key.</param>
        /// <param name="metaKey">The meta key.</param>
        /// <returns></returns>
        public string GetParameterMetaData(string nodeKey, string metaKey)
        {
            if (_parameterMetaDataXML != null)
            {
                // Use this to find the endpoint node we are looking for
                // Either it will be pulled from a file in the ArduPlane hierarchy or the ArduCopter hierarchy
                try
                {
                    MainV2.Firmwares selected = MainV2.comPort.MAV.cs.firmware;

                    var element = _parameterMetaDataXML.Element("Params").Element(selected.ToString());
                    if (element != null && element.HasElements)
                    {
                        var node = element.Element(nodeKey);
                        if (node != null && node.HasElements)
                        {
                            var metaValue = node.Element(metaKey);
                            if (metaValue != null)
                            {
                                return(metaValue.Value);
                            }
                        }
                    }
                }
                catch { } // Exception System.ArgumentException: '' is an invalid expanded name.
            }
            return(string.Empty);
        }
Пример #2
0
        public static List <KeyValuePair <int, string> > getModesList(MainV2.Firmwares firmware)
        {
            log.Info("getModesList Called");

            if (firmware == MainV2.Firmwares.PX4)
            {
                /*
                 * union px4_custom_mode {
                 * struct {
                 * uint16_t reserved;
                 * uint8_t main_mode;
                 * uint8_t sub_mode;
                 * };
                 * uint32_t data;
                 * float data_float;
                 * };
                 */


                var temp = new List <KeyValuePair <int, string> >()
                {
                    new KeyValuePair <int, string>((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_MANUAL << 16, "Manual"),
                    new KeyValuePair <int, string>((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_ACRO << 16, "Acro"),
                    new KeyValuePair <int, string>((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_STABILIZED << 16,
                                                   "Stabalized"),
                    new KeyValuePair <int, string>((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_RATTITUDE << 16,
                                                   "Rattitude"),
                    new KeyValuePair <int, string>((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_ALTCTL << 16,
                                                   "Altitude Control"),
                    new KeyValuePair <int, string>((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_POSCTL << 16,
                                                   "Position Control"),
                    new KeyValuePair <int, string>((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_OFFBOARD << 16,
                                                   "Offboard Control"),
                    new KeyValuePair <int, string>(
                        ((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_AUTO << 16) +
                        (int)PX4_CUSTOM_SUB_MODE_AUTO.PX4_CUSTOM_SUB_MODE_AUTO_READY << 24, "Auto: Ready"),
                    new KeyValuePair <int, string>(
                        ((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_AUTO << 16) +
                        (int)PX4_CUSTOM_SUB_MODE_AUTO.PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF << 24, "Auto: Takeoff"),
                    new KeyValuePair <int, string>(
                        ((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_AUTO << 16) +
                        (int)PX4_CUSTOM_SUB_MODE_AUTO.PX4_CUSTOM_SUB_MODE_AUTO_LOITER << 24, "Loiter"),
                    new KeyValuePair <int, string>(
                        ((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_AUTO << 16) +
                        (int)PX4_CUSTOM_SUB_MODE_AUTO.PX4_CUSTOM_SUB_MODE_AUTO_MISSION << 24, "Auto"),
                    new KeyValuePair <int, string>(
                        ((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_AUTO << 16) +
                        (int)PX4_CUSTOM_SUB_MODE_AUTO.PX4_CUSTOM_SUB_MODE_AUTO_RTL << 24, "RTL"),
                    new KeyValuePair <int, string>(
                        ((int)PX4_CUSTOM_MAIN_MODE.PX4_CUSTOM_MAIN_MODE_AUTO << 16) +
                        (int)PX4_CUSTOM_SUB_MODE_AUTO.PX4_CUSTOM_SUB_MODE_AUTO_LAND << 24, "Auto: Landing")
                };

                return(temp);
            }
            else if (firmware == MainV2.Firmwares.ArduPlane)
            {
                var flightModes = Utilities.ParameterMetaDataRepository.GetParameterOptionsInt("FLTMODE1",
                                                                                               firmware.ToString());
                flightModes.Add(new KeyValuePair <int, string>(16, "INITIALISING"));

                flightModes.Add(new KeyValuePair <int, string>(17, "QStabilize"));
                flightModes.Add(new KeyValuePair <int, string>(18, "QHover"));
                flightModes.Add(new KeyValuePair <int, string>(19, "QLoiter"));
                flightModes.Add(new KeyValuePair <int, string>(20, "QLand"));
                flightModes.Add(new KeyValuePair <int, string>(21, "QRTL"));

                return(flightModes);
            }
            else if (firmware == MainV2.Firmwares.Ateryx)
            {
                var flightModes = Utilities.ParameterMetaDataRepository.GetParameterOptionsInt("FLTMODE1",
                                                                                               firmware.ToString()); //same as apm
                return(flightModes);
            }
            else if (firmware == MainV2.Firmwares.ArduCopter2)
            {
                var flightModes = Utilities.ParameterMetaDataRepository.GetParameterOptionsInt("FLTMODE1",
                                                                                               firmware.ToString());
                return(flightModes);
            }
            else if (firmware == MainV2.Firmwares.ArduRover)
            {
                var flightModes = Utilities.ParameterMetaDataRepository.GetParameterOptionsInt("MODE1",
                                                                                               firmware.ToString());
                return(flightModes);
            }
            else if (firmware == MainV2.Firmwares.ArduTracker)
            {
                var temp = new List <KeyValuePair <int, string> >();
                temp.Add(new KeyValuePair <int, string>(0, "MANUAL"));
                temp.Add(new KeyValuePair <int, string>(1, "STOP"));
                temp.Add(new KeyValuePair <int, string>(2, "SCAN"));
                temp.Add(new KeyValuePair <int, string>(3, "SERVO_TEST"));
                temp.Add(new KeyValuePair <int, string>(10, "AUTO"));
                temp.Add(new KeyValuePair <int, string>(16, "INITIALISING"));

                return(temp);
            }

            return(null);
        }