diff --git a/ground/src/plugins/uavobjects/OPLogConvert.m b/ground/src/plugins/uavobjects/OPLogConvert.m deleted file mode 100644 index c9795be8f..000000000 --- a/ground/src/plugins/uavobjects/OPLogConvert.m +++ /dev/null @@ -1,1467 +0,0 @@ -function [] = OPLogConvert() - %% Define indices and arrays of structures to hold data - - actuatorcommandIdx = 1; - ActuatorCommand.timestamp = 0; - ActuatorCommand(1).Channel = zeros(1,8); - ActuatorCommand(1).UpdateTime = 0; - ActuatorCommand(1).MaxUpdateTime = 0; - ActuatorCommand(1).NumFailedUpdates = 0; - - actuatordesiredIdx = 1; - ActuatorDesired.timestamp = 0; - ActuatorDesired(1).Roll = 0; - ActuatorDesired(1).Pitch = 0; - ActuatorDesired(1).Yaw = 0; - ActuatorDesired(1).Throttle = 0; - ActuatorDesired(1).UpdateTime = 0; - ActuatorDesired(1).NumLongUpdates = 0; - - actuatorsettingsIdx = 1; - ActuatorSettings.timestamp = 0; - ActuatorSettings(1).FixedWingRoll1 = 0; - ActuatorSettings(1).FixedWingRoll2 = 0; - ActuatorSettings(1).FixedWingPitch1 = 0; - ActuatorSettings(1).FixedWingPitch2 = 0; - ActuatorSettings(1).FixedWingYaw = 0; - ActuatorSettings(1).FixedWingThrottle = 0; - ActuatorSettings(1).VTOLMotorN = 0; - ActuatorSettings(1).VTOLMotorNE = 0; - ActuatorSettings(1).VTOLMotorE = 0; - ActuatorSettings(1).VTOLMotorSE = 0; - ActuatorSettings(1).VTOLMotorS = 0; - ActuatorSettings(1).VTOLMotorSW = 0; - ActuatorSettings(1).VTOLMotorW = 0; - ActuatorSettings(1).VTOLMotorNW = 0; - ActuatorSettings(1).ChannelUpdateFreq = zeros(1,2); - ActuatorSettings(1).ChannelMax = zeros(1,8); - ActuatorSettings(1).ChannelNeutral = zeros(1,8); - ActuatorSettings(1).ChannelMin = zeros(1,8); - ActuatorSettings(1).ChannelType = zeros(1,8); - ActuatorSettings(1).ChannelAddr = zeros(1,8); - - ahrscalibrationIdx = 1; - AHRSCalibration.timestamp = 0; - AHRSCalibration(1).measure_var = 0; - AHRSCalibration(1).accel_bias = zeros(1,3); - AHRSCalibration(1).accel_scale = zeros(1,3); - AHRSCalibration(1).accel_var = zeros(1,3); - AHRSCalibration(1).gyro_bias = zeros(1,3); - AHRSCalibration(1).gyro_scale = zeros(1,3); - AHRSCalibration(1).gyro_var = zeros(1,3); - AHRSCalibration(1).gyro_tempcompfactor = zeros(1,3); - AHRSCalibration(1).mag_bias = zeros(1,3); - AHRSCalibration(1).mag_scale = zeros(1,3); - AHRSCalibration(1).mag_var = zeros(1,3); - AHRSCalibration(1).vel_var = 0; - AHRSCalibration(1).pos_var = 0; - - ahrssettingsIdx = 1; - AHRSSettings.timestamp = 0; - AHRSSettings(1).Algorithm = 0; - AHRSSettings(1).Downsampling = 0; - AHRSSettings(1).UpdatePeriod = 0; - AHRSSettings(1).BiasCorrectedRaw = 0; - AHRSSettings(1).YawBias = 0; - AHRSSettings(1).PitchBias = 0; - AHRSSettings(1).RollBias = 0; - - ahrsstatusIdx = 1; - AhrsStatus.timestamp = 0; - AhrsStatus(1).SerialNumber = zeros(1,8); - AhrsStatus(1).CPULoad = 0; - AhrsStatus(1).RunningTime = 0; - AhrsStatus(1).IdleTimePerCyle = 0; - AhrsStatus(1).RunningTimePerCyle = 0; - AhrsStatus(1).DroppedUpdates = 0; - AhrsStatus(1).LinkRunning = 0; - AhrsStatus(1).AhrsKickstarts = 0; - AhrsStatus(1).AhrsCrcErrors = 0; - AhrsStatus(1).AhrsRetries = 0; - AhrsStatus(1).AhrsInvalidPackets = 0; - AhrsStatus(1).OpCrcErrors = 0; - AhrsStatus(1).OpRetries = 0; - AhrsStatus(1).OpInvalidPackets = 0; - - attitudeactualIdx = 1; - AttitudeActual.timestamp = 0; - AttitudeActual(1).q1 = 0; - AttitudeActual(1).q2 = 0; - AttitudeActual(1).q3 = 0; - AttitudeActual(1).q4 = 0; - AttitudeActual(1).Roll = 0; - AttitudeActual(1).Pitch = 0; - AttitudeActual(1).Yaw = 0; - - attitudedesiredIdx = 1; - AttitudeDesired.timestamp = 0; - AttitudeDesired(1).Roll = 0; - AttitudeDesired(1).Pitch = 0; - AttitudeDesired(1).Yaw = 0; - AttitudeDesired(1).Throttle = 0; - - attituderawIdx = 1; - AttitudeRaw.timestamp = 0; - AttitudeRaw(1).magnetometers = zeros(1,3); - AttitudeRaw(1).gyros = zeros(1,3); - AttitudeRaw(1).gyros_filtered = zeros(1,3); - AttitudeRaw(1).gyrotemp = zeros(1,2); - AttitudeRaw(1).accels = zeros(1,3); - AttitudeRaw(1).accels_filtered = zeros(1,3); - - baroaltitudeIdx = 1; - BaroAltitude.timestamp = 0; - BaroAltitude(1).Altitude = 0; - BaroAltitude(1).Temperature = 0; - BaroAltitude(1).Pressure = 0; - - batterysettingsIdx = 1; - BatterySettings.timestamp = 0; - BatterySettings(1).BatteryVoltage = 0; - BatterySettings(1).BatteryCapacity = 0; - BatterySettings(1).BatteryType = 0; - BatterySettings(1).Calibrations = zeros(1,2); - - firmwareiapobjIdx = 1; - FirmwareIAPObj.timestamp = 0; - FirmwareIAPObj(1).Command = 0; - FirmwareIAPObj(1).Description = zeros(1,100); - FirmwareIAPObj(1).HWVersion = 0; - FirmwareIAPObj(1).Target = 0; - FirmwareIAPObj(1).ArmReset = 0; - FirmwareIAPObj(1).crc = 0; - - flightbatterystateIdx = 1; - FlightBatteryState.timestamp = 0; - FlightBatteryState(1).Voltage = 0; - FlightBatteryState(1).Current = 0; - FlightBatteryState(1).PeakCurrent = 0; - FlightBatteryState(1).AvgCurrent = 0; - FlightBatteryState(1).ConsumedEnergy = 0; - FlightBatteryState(1).EstimatedFlightTime = 0; - - flightplancontrolIdx = 1; - FlightPlanControl.timestamp = 0; - FlightPlanControl(1).Test = 0; - - flightplansettingsIdx = 1; - FlightPlanSettings.timestamp = 0; - FlightPlanSettings(1).Test = 0; - - flightplanstatusIdx = 1; - FlightPlanStatus.timestamp = 0; - FlightPlanStatus(1).Status = 0; - FlightPlanStatus(1).ErrorType = 0; - FlightPlanStatus(1).ErrorFileID = 0; - FlightPlanStatus(1).ErrorLineNum = 0; - FlightPlanStatus(1).Debug = 0; - - flighttelemetrystatsIdx = 1; - FlightTelemetryStats.timestamp = 0; - FlightTelemetryStats(1).Status = 0; - FlightTelemetryStats(1).TxDataRate = 0; - FlightTelemetryStats(1).RxDataRate = 0; - FlightTelemetryStats(1).TxFailures = 0; - FlightTelemetryStats(1).RxFailures = 0; - FlightTelemetryStats(1).TxRetries = 0; - - gcstelemetrystatsIdx = 1; - GCSTelemetryStats.timestamp = 0; - GCSTelemetryStats(1).Status = 0; - GCSTelemetryStats(1).TxDataRate = 0; - GCSTelemetryStats(1).RxDataRate = 0; - GCSTelemetryStats(1).TxFailures = 0; - GCSTelemetryStats(1).RxFailures = 0; - GCSTelemetryStats(1).TxRetries = 0; - - gpspositionIdx = 1; - GPSPosition.timestamp = 0; - GPSPosition(1).Status = 0; - GPSPosition(1).Latitude = 0; - GPSPosition(1).Longitude = 0; - GPSPosition(1).Altitude = 0; - GPSPosition(1).GeoidSeparation = 0; - GPSPosition(1).Heading = 0; - GPSPosition(1).Groundspeed = 0; - GPSPosition(1).Satellites = 0; - GPSPosition(1).PDOP = 0; - GPSPosition(1).HDOP = 0; - GPSPosition(1).VDOP = 0; - - gpssatellitesIdx = 1; - GPSSatellites.timestamp = 0; - GPSSatellites(1).SatsInView = 0; - GPSSatellites(1).PRN = zeros(1,16); - GPSSatellites(1).Elevation = zeros(1,16); - GPSSatellites(1).Azimuth = zeros(1,16); - GPSSatellites(1).SNR = zeros(1,16); - - gpstimeIdx = 1; - GPSTime.timestamp = 0; - GPSTime(1).Month = 0; - GPSTime(1).Day = 0; - GPSTime(1).Year = 0; - GPSTime(1).Hour = 0; - GPSTime(1).Minute = 0; - GPSTime(1).Second = 0; - - guidancesettingsIdx = 1; - GuidanceSettings.timestamp = 0; - GuidanceSettings(1).GuidanceMode = 0; - GuidanceSettings(1).MaxGroundspeed = 0; - GuidanceSettings(1).GroundVelocityP = 0; - GuidanceSettings(1).MaxVerticalSpeed = 0; - GuidanceSettings(1).VertVelocityP = 0; - GuidanceSettings(1).VelP = 0; - GuidanceSettings(1).VelI = 0; - GuidanceSettings(1).VelD = 0; - GuidanceSettings(1).DownP = 0; - GuidanceSettings(1).DownI = 0; - GuidanceSettings(1).DownD = 0; - GuidanceSettings(1).MaxVelIntegral = 0; - GuidanceSettings(1).MaxThrottleIntegral = 0; - GuidanceSettings(1).VelUpdatePeriod = 0; - GuidanceSettings(1).VelPIDUpdatePeriod = 0; - - homelocationIdx = 1; - HomeLocation.timestamp = 0; - HomeLocation(1).Set = 0; - HomeLocation(1).Latitude = 0; - HomeLocation(1).Longitude = 0; - HomeLocation(1).Altitude = 0; - HomeLocation(1).ECEF = zeros(1,3); - HomeLocation(1).RNE = zeros(1,9); - HomeLocation(1).Be = zeros(1,3); - - i2cstatsIdx = 1; - I2CStats.timestamp = 0; - I2CStats(1).event_errors = 0; - I2CStats(1).fsm_errors = 0; - I2CStats(1).irq_errors = 0; - I2CStats(1).last_error_type = 0; - I2CStats(1).evirq_log = zeros(1,5); - I2CStats(1).erirq_log = zeros(1,5); - I2CStats(1).event_log = zeros(1,5); - I2CStats(1).state_log = zeros(1,5); - - manualcontrolcommandIdx = 1; - ManualControlCommand.timestamp = 0; - ManualControlCommand(1).Connected = 0; - ManualControlCommand(1).Armed = 0; - ManualControlCommand(1).Roll = 0; - ManualControlCommand(1).Pitch = 0; - ManualControlCommand(1).Yaw = 0; - ManualControlCommand(1).Throttle = 0; - ManualControlCommand(1).FlightMode = 0; - ManualControlCommand(1).StabilizationSettings = zeros(1,3); - ManualControlCommand(1).Accessory1 = 0; - ManualControlCommand(1).Accessory2 = 0; - ManualControlCommand(1).Accessory3 = 0; - ManualControlCommand(1).Channel = zeros(1,8); - - manualcontrolsettingsIdx = 1; - ManualControlSettings.timestamp = 0; - ManualControlSettings(1).InputMode = 0; - ManualControlSettings(1).Roll = 0; - ManualControlSettings(1).Pitch = 0; - ManualControlSettings(1).Yaw = 0; - ManualControlSettings(1).Throttle = 0; - ManualControlSettings(1).FlightMode = 0; - ManualControlSettings(1).Accessory1 = 0; - ManualControlSettings(1).Accessory2 = 0; - ManualControlSettings(1).Accessory3 = 0; - ManualControlSettings(1).Pos1StabilizationSettings = zeros(1,3); - ManualControlSettings(1).Pos2StabilizationSettings = zeros(1,3); - ManualControlSettings(1).Pos3StabilizationSettings = zeros(1,3); - ManualControlSettings(1).Pos1FlightMode = 0; - ManualControlSettings(1).Pos2FlightMode = 0; - ManualControlSettings(1).Pos3FlightMode = 0; - ManualControlSettings(1).ChannelMax = zeros(1,8); - ManualControlSettings(1).ChannelNeutral = zeros(1,8); - ManualControlSettings(1).ChannelMin = zeros(1,8); - ManualControlSettings(1).ArmedTimeout = 0; - - mixersettingsIdx = 1; - MixerSettings.timestamp = 0; - MixerSettings(1).MaxAccel = 0; - MixerSettings(1).FeedForward = 0; - MixerSettings(1).AccelTime = 0; - MixerSettings(1).DecelTime = 0; - MixerSettings(1).ThrottleCurve1 = zeros(1,5); - MixerSettings(1).ThrottleCurve2 = zeros(1,5); - MixerSettings(1).Mixer1Type = 0; - MixerSettings(1).Mixer1Vector = zeros(1,5); - MixerSettings(1).Mixer2Type = 0; - MixerSettings(1).Mixer2Vector = zeros(1,5); - MixerSettings(1).Mixer3Type = 0; - MixerSettings(1).Mixer3Vector = zeros(1,5); - MixerSettings(1).Mixer4Type = 0; - MixerSettings(1).Mixer4Vector = zeros(1,5); - MixerSettings(1).Mixer5Type = 0; - MixerSettings(1).Mixer5Vector = zeros(1,5); - MixerSettings(1).Mixer6Type = 0; - MixerSettings(1).Mixer6Vector = zeros(1,5); - MixerSettings(1).Mixer7Type = 0; - MixerSettings(1).Mixer7Vector = zeros(1,5); - MixerSettings(1).Mixer8Type = 0; - MixerSettings(1).Mixer8Vector = zeros(1,5); - - mixerstatusIdx = 1; - MixerStatus.timestamp = 0; - MixerStatus(1).Mixer1 = 0; - MixerStatus(1).Mixer2 = 0; - MixerStatus(1).Mixer3 = 0; - MixerStatus(1).Mixer4 = 0; - MixerStatus(1).Mixer5 = 0; - MixerStatus(1).Mixer6 = 0; - MixerStatus(1).Mixer7 = 0; - MixerStatus(1).Mixer8 = 0; - - objectpersistenceIdx = 1; - ObjectPersistence.timestamp = 0; - ObjectPersistence(1).Operation = 0; - ObjectPersistence(1).Selection = 0; - ObjectPersistence(1).ObjectID = 0; - ObjectPersistence(1).InstanceID = 0; - - pipxtrememodemsettingsIdx = 1; - PipXtremeModemSettings.timestamp = 0; - PipXtremeModemSettings(1).Mode = 0; - PipXtremeModemSettings(1).Serial_Baudrate = 0; - PipXtremeModemSettings(1).Frequency_Calibration = 0; - PipXtremeModemSettings(1).Frequency_Min = 0; - PipXtremeModemSettings(1).Frequency_Max = 0; - PipXtremeModemSettings(1).Frequency = 0; - PipXtremeModemSettings(1).Max_RF_Bandwidth = 0; - PipXtremeModemSettings(1).Max_Tx_Power = 0; - PipXtremeModemSettings(1).Tx_Data_Wait = 0; - PipXtremeModemSettings(1).AES_Encryption = 0; - PipXtremeModemSettings(1).AES_EncryptionKey = zeros(1,16); - PipXtremeModemSettings(1).Paired_Serial_Number = 0; - - pipxtrememodemstatusIdx = 1; - PipXtremeModemStatus.timestamp = 0; - PipXtremeModemStatus(1).Firmware_Version_Major = 0; - PipXtremeModemStatus(1).Firmware_Version_Minor = 0; - PipXtremeModemStatus(1).Serial_Number = 0; - PipXtremeModemStatus(1).Up_Time = 0; - PipXtremeModemStatus(1).Frequency = 0; - PipXtremeModemStatus(1).RF_Bandwidth = 0; - PipXtremeModemStatus(1).Tx_Power = 0; - PipXtremeModemStatus(1).State = 0; - PipXtremeModemStatus(1).Tx_Retry = 0; - PipXtremeModemStatus(1).Tx_Data_Rate = 0; - PipXtremeModemStatus(1).Rx_Data_Rate = 0; - - positionactualIdx = 1; - PositionActual.timestamp = 0; - PositionActual(1).North = 0; - PositionActual(1).East = 0; - PositionActual(1).Down = 0; - - positiondesiredIdx = 1; - PositionDesired.timestamp = 0; - PositionDesired(1).North = 0; - PositionDesired(1).East = 0; - PositionDesired(1).Down = 0; - - ratedesiredIdx = 1; - RateDesired.timestamp = 0; - RateDesired(1).Roll = 0; - RateDesired(1).Pitch = 0; - RateDesired(1).Yaw = 0; - - stabilizationsettingsIdx = 1; - StabilizationSettings.timestamp = 0; - StabilizationSettings(1).RollMax = 0; - StabilizationSettings(1).PitchMax = 0; - StabilizationSettings(1).YawMax = 0; - StabilizationSettings(1).ManualRate = zeros(1,3); - StabilizationSettings(1).MaximumRate = zeros(1,3); - StabilizationSettings(1).RollRatePI = zeros(1,3); - StabilizationSettings(1).PitchRatePI = zeros(1,3); - StabilizationSettings(1).YawRatePI = zeros(1,3); - StabilizationSettings(1).RollPI = zeros(1,3); - StabilizationSettings(1).PitchPI = zeros(1,3); - StabilizationSettings(1).YawPI = zeros(1,3); - - systemalarmsIdx = 1; - SystemAlarms.timestamp = 0; - SystemAlarms(1).Alarm = zeros(1,14); - - systemsettingsIdx = 1; - SystemSettings.timestamp = 0; - SystemSettings(1).AirframeType = 0; - - systemstatsIdx = 1; - SystemStats.timestamp = 0; - SystemStats(1).FlightTime = 0; - SystemStats(1).HeapRemaining = 0; - SystemStats(1).CPULoad = 0; - - taskinfoIdx = 1; - TaskInfo.timestamp = 0; - TaskInfo(1).StackRemaining = zeros(1,13); - TaskInfo(1).Running = zeros(1,13); - - telemetrysettingsIdx = 1; - TelemetrySettings.timestamp = 0; - TelemetrySettings(1).Speed = 0; - - velocityactualIdx = 1; - VelocityActual.timestamp = 0; - VelocityActual(1).North = 0; - VelocityActual(1).East = 0; - VelocityActual(1).Down = 0; - - velocitydesiredIdx = 1; - VelocityDesired.timestamp = 0; - VelocityDesired(1).North = 0; - VelocityDesired(1).East = 0; - VelocityDesired(1).Down = 0; - - watchdogstatusIdx = 1; - WatchdogStatus.timestamp = 0; - WatchdogStatus(1).BootupFlags = 0; - WatchdogStatus(1).ActiveFlags = 0; - - - %% Open file - %fid = fopen('log.opl'); - [FileName,PathName,FilterIndex] = uigetfile('*.opl'); - logfile = strcat(PathName,FileName); - fid = fopen(logfile); - - while (1) - %% Read logging header - timestamp = fread(fid, 1, 'uint32'); - if (feof(fid)); break; end - datasize = fread(fid, 1, 'int64'); - - - %% Read message header - % get sync field (0x3C, 1 byte) - sync = fread(fid, 1, 'uint8'); - if sync ~= hex2dec('3C') - disp ('Wrong sync byte'); - return - end - % get msg type (quint8 1 byte ) should be 0x20, ignore the rest? - msgType = fread(fid, 1, 'uint8'); - if msgType ~= hex2dec('20') - disp ('Wrong msgType'); - return - end - % get msg size (quint16 2 bytes) excludes crc, include msg header and data payload - msgSize = fread(fid, 1, 'uint16'); - % get obj id (quint32 4 bytes) - objID = fread(fid, 1, 'uint32'); - - - %% Read object - switch objID - case 3907024856 - ActuatorCommand(actuatorcommandIdx) = ReadActuatorCommandObject(fid, timestamp); - actuatorcommandIdx = actuatorcommandIdx + 1; - case 3562104706 - ActuatorDesired(actuatordesiredIdx) = ReadActuatorDesiredObject(fid, timestamp); - actuatordesiredIdx = actuatordesiredIdx + 1; - case 844831578 - ActuatorSettings(actuatorsettingsIdx) = ReadActuatorSettingsObject(fid, timestamp); - actuatorsettingsIdx = actuatorsettingsIdx + 1; - case 806362034 - AHRSCalibration(ahrscalibrationIdx) = ReadAHRSCalibrationObject(fid, timestamp); - ahrscalibrationIdx = ahrscalibrationIdx + 1; - case 3741078856 - AHRSSettings(ahrssettingsIdx) = ReadAHRSSettingsObject(fid, timestamp); - ahrssettingsIdx = ahrssettingsIdx + 1; - case 933623714 - AhrsStatus(ahrsstatusIdx) = ReadAhrsStatusObject(fid, timestamp); - ahrsstatusIdx = ahrsstatusIdx + 1; - case 4233858292 - AttitudeActual(attitudeactualIdx) = ReadAttitudeActualObject(fid, timestamp); - attitudeactualIdx = attitudeactualIdx + 1; - case 1412270808 - AttitudeDesired(attitudedesiredIdx) = ReadAttitudeDesiredObject(fid, timestamp); - attitudedesiredIdx = attitudedesiredIdx + 1; - case 1323193976 - AttitudeRaw(attituderawIdx) = ReadAttitudeRawObject(fid, timestamp); - attituderawIdx = attituderawIdx + 1; - case 3980666102 - BaroAltitude(baroaltitudeIdx) = ReadBaroAltitudeObject(fid, timestamp); - baroaltitudeIdx = baroaltitudeIdx + 1; - case 2784959898 - BatterySettings(batterysettingsIdx) = ReadBatterySettingsObject(fid, timestamp); - batterysettingsIdx = batterysettingsIdx + 1; - case 879185696 - FirmwareIAPObj(firmwareiapobjIdx) = ReadFirmwareIAPObjObject(fid, timestamp); - firmwareiapobjIdx = firmwareiapobjIdx + 1; - case 126985486 - FlightBatteryState(flightbatterystateIdx) = ReadFlightBatteryStateObject(fid, timestamp); - flightbatterystateIdx = flightbatterystateIdx + 1; - case 4125349796 - FlightPlanControl(flightplancontrolIdx) = ReadFlightPlanControlObject(fid, timestamp); - flightplancontrolIdx = flightplancontrolIdx + 1; - case 2234942498 - FlightPlanSettings(flightplansettingsIdx) = ReadFlightPlanSettingsObject(fid, timestamp); - flightplansettingsIdx = flightplansettingsIdx + 1; - case 2726772894 - FlightPlanStatus(flightplanstatusIdx) = ReadFlightPlanStatusObject(fid, timestamp); - flightplanstatusIdx = flightplanstatusIdx + 1; - case 1712072286 - FlightTelemetryStats(flighttelemetrystatsIdx) = ReadFlightTelemetryStatsObject(fid, timestamp); - flighttelemetrystatsIdx = flighttelemetrystatsIdx + 1; - case 1998458950 - GCSTelemetryStats(gcstelemetrystatsIdx) = ReadGCSTelemetryStatsObject(fid, timestamp); - gcstelemetrystatsIdx = gcstelemetrystatsIdx + 1; - case 3041480770 - GPSPosition(gpspositionIdx) = ReadGPSPositionObject(fid, timestamp); - gpspositionIdx = gpspositionIdx + 1; - case 3593446318 - GPSSatellites(gpssatellitesIdx) = ReadGPSSatellitesObject(fid, timestamp); - gpssatellitesIdx = gpssatellitesIdx + 1; - case 1459613858 - GPSTime(gpstimeIdx) = ReadGPSTimeObject(fid, timestamp); - gpstimeIdx = gpstimeIdx + 1; - case 2071403670 - GuidanceSettings(guidancesettingsIdx) = ReadGuidanceSettingsObject(fid, timestamp); - guidancesettingsIdx = guidancesettingsIdx + 1; - case 3590360786 - HomeLocation(homelocationIdx) = ReadHomeLocationObject(fid, timestamp); - homelocationIdx = homelocationIdx + 1; - case 122889918 - I2CStats(i2cstatsIdx) = ReadI2CStatsObject(fid, timestamp); - i2cstatsIdx = i2cstatsIdx + 1; - case 2841592332 - ManualControlCommand(manualcontrolcommandIdx) = ReadManualControlCommandObject(fid, timestamp); - manualcontrolcommandIdx = manualcontrolcommandIdx + 1; - case 157988682 - ManualControlSettings(manualcontrolsettingsIdx) = ReadManualControlSettingsObject(fid, timestamp); - manualcontrolsettingsIdx = manualcontrolsettingsIdx + 1; - case 1336817486 - MixerSettings(mixersettingsIdx) = ReadMixerSettingsObject(fid, timestamp); - mixersettingsIdx = mixersettingsIdx + 1; - case 4137893648 - MixerStatus(mixerstatusIdx) = ReadMixerStatusObject(fid, timestamp); - mixerstatusIdx = mixerstatusIdx + 1; - case 572614706 - ObjectPersistence(objectpersistenceIdx) = ReadObjectPersistenceObject(fid, timestamp); - objectpersistenceIdx = objectpersistenceIdx + 1; - case 444830632 - PipXtremeModemSettings(pipxtrememodemsettingsIdx) = ReadPipXtremeModemSettingsObject(fid, timestamp); - pipxtrememodemsettingsIdx = pipxtrememodemsettingsIdx + 1; - case 2490854928 - PipXtremeModemStatus(pipxtrememodemstatusIdx) = ReadPipXtremeModemStatusObject(fid, timestamp); - pipxtrememodemstatusIdx = pipxtrememodemstatusIdx + 1; - case 3765671478 - PositionActual(positionactualIdx) = ReadPositionActualObject(fid, timestamp); - positionactualIdx = positionactualIdx + 1; - case 801433018 - PositionDesired(positiondesiredIdx) = ReadPositionDesiredObject(fid, timestamp); - positiondesiredIdx = positiondesiredIdx + 1; - case 3124868380 - RateDesired(ratedesiredIdx) = ReadRateDesiredObject(fid, timestamp); - ratedesiredIdx = ratedesiredIdx + 1; - case 3792991236 - StabilizationSettings(stabilizationsettingsIdx) = ReadStabilizationSettingsObject(fid, timestamp); - stabilizationsettingsIdx = stabilizationsettingsIdx + 1; - case 2311314672 - SystemAlarms(systemalarmsIdx) = ReadSystemAlarmsObject(fid, timestamp); - systemalarmsIdx = systemalarmsIdx + 1; - case 59202798 - SystemSettings(systemsettingsIdx) = ReadSystemSettingsObject(fid, timestamp); - systemsettingsIdx = systemsettingsIdx + 1; - case 680908530 - SystemStats(systemstatsIdx) = ReadSystemStatsObject(fid, timestamp); - systemstatsIdx = systemstatsIdx + 1; - case 1358273008 - TaskInfo(taskinfoIdx) = ReadTaskInfoObject(fid, timestamp); - taskinfoIdx = taskinfoIdx + 1; - case 2785592614 - TelemetrySettings(telemetrysettingsIdx) = ReadTelemetrySettingsObject(fid, timestamp); - telemetrysettingsIdx = telemetrysettingsIdx + 1; - case 1207999624 - VelocityActual(velocityactualIdx) = ReadVelocityActualObject(fid, timestamp); - velocityactualIdx = velocityactualIdx + 1; - case 305094202 - VelocityDesired(velocitydesiredIdx) = ReadVelocityDesiredObject(fid, timestamp); - velocitydesiredIdx = velocitydesiredIdx + 1; - case 3594971408 - WatchdogStatus(watchdogstatusIdx) = ReadWatchdogStatusObject(fid, timestamp); - watchdogstatusIdx = watchdogstatusIdx + 1; - - otherwise - disp('Unknown object ID'); - msgBytesLeft = datasize - 1 - 1 - 2 - 4; - fread(fid, msgBytesLeft, 'uint8'); - end - - end - - %% Clean Up and Save mat file - fclose(fid); - - matfile = strrep(logfile,'opl','mat'); - save(matfile ,'ActuatorCommand','ActuatorDesired','ActuatorSettings','AHRSCalibration','AHRSSettings','AhrsStatus','AttitudeActual','AttitudeDesired','AttitudeRaw','BaroAltitude','BatterySettings','FirmwareIAPObj','FlightBatteryState','FlightPlanControl','FlightPlanSettings','FlightPlanStatus','FlightTelemetryStats','GCSTelemetryStats','GPSPosition','GPSSatellites','GPSTime','GuidanceSettings','HomeLocation','I2CStats','ManualControlCommand','ManualControlSettings','MixerSettings','MixerStatus','ObjectPersistence','PipXtremeModemSettings','PipXtremeModemStatus','PositionActual','PositionDesired','RateDesired','StabilizationSettings','SystemAlarms','SystemSettings','SystemStats','TaskInfo','TelemetrySettings','VelocityActual','VelocityDesired','WatchdogStatus'); - -end - - -%% Object reading functions -function [ActuatorCommand] = ReadActuatorCommandObject(fid, timestamp) - if 1 - headerSize = 8; - else - ActuatorCommand.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - ActuatorCommand.timestamp = timestamp; - ActuatorCommand.Channel = double(fread(fid, 8, 'int16')); - ActuatorCommand.UpdateTime = double(fread(fid, 1, 'uint8')); - ActuatorCommand.MaxUpdateTime = double(fread(fid, 1, 'uint8')); - ActuatorCommand.NumFailedUpdates = double(fread(fid, 1, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [ActuatorDesired] = ReadActuatorDesiredObject(fid, timestamp) - if 1 - headerSize = 8; - else - ActuatorDesired.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - ActuatorDesired.timestamp = timestamp; - ActuatorDesired.Roll = double(fread(fid, 1, 'float32')); - ActuatorDesired.Pitch = double(fread(fid, 1, 'float32')); - ActuatorDesired.Yaw = double(fread(fid, 1, 'float32')); - ActuatorDesired.Throttle = double(fread(fid, 1, 'float32')); - ActuatorDesired.UpdateTime = double(fread(fid, 1, 'float32')); - ActuatorDesired.NumLongUpdates = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [ActuatorSettings] = ReadActuatorSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - ActuatorSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - ActuatorSettings.timestamp = timestamp; - ActuatorSettings.FixedWingRoll1 = double(fread(fid, 1, 'uint8')); - ActuatorSettings.FixedWingRoll2 = double(fread(fid, 1, 'uint8')); - ActuatorSettings.FixedWingPitch1 = double(fread(fid, 1, 'uint8')); - ActuatorSettings.FixedWingPitch2 = double(fread(fid, 1, 'uint8')); - ActuatorSettings.FixedWingYaw = double(fread(fid, 1, 'uint8')); - ActuatorSettings.FixedWingThrottle = double(fread(fid, 1, 'uint8')); - ActuatorSettings.VTOLMotorN = double(fread(fid, 1, 'uint8')); - ActuatorSettings.VTOLMotorNE = double(fread(fid, 1, 'uint8')); - ActuatorSettings.VTOLMotorE = double(fread(fid, 1, 'uint8')); - ActuatorSettings.VTOLMotorSE = double(fread(fid, 1, 'uint8')); - ActuatorSettings.VTOLMotorS = double(fread(fid, 1, 'uint8')); - ActuatorSettings.VTOLMotorSW = double(fread(fid, 1, 'uint8')); - ActuatorSettings.VTOLMotorW = double(fread(fid, 1, 'uint8')); - ActuatorSettings.VTOLMotorNW = double(fread(fid, 1, 'uint8')); - ActuatorSettings.ChannelUpdateFreq = double(fread(fid, 2, 'int16')); - ActuatorSettings.ChannelMax = double(fread(fid, 8, 'int16')); - ActuatorSettings.ChannelNeutral = double(fread(fid, 8, 'int16')); - ActuatorSettings.ChannelMin = double(fread(fid, 8, 'int16')); - ActuatorSettings.ChannelType = double(fread(fid, 8, 'uint8')); - ActuatorSettings.ChannelAddr = double(fread(fid, 8, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [AHRSCalibration] = ReadAHRSCalibrationObject(fid, timestamp) - if 1 - headerSize = 8; - else - AHRSCalibration.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - AHRSCalibration.timestamp = timestamp; - AHRSCalibration.measure_var = double(fread(fid, 1, 'uint8')); - AHRSCalibration.accel_bias = double(fread(fid, 3, 'float32')); - AHRSCalibration.accel_scale = double(fread(fid, 3, 'float32')); - AHRSCalibration.accel_var = double(fread(fid, 3, 'float32')); - AHRSCalibration.gyro_bias = double(fread(fid, 3, 'float32')); - AHRSCalibration.gyro_scale = double(fread(fid, 3, 'float32')); - AHRSCalibration.gyro_var = double(fread(fid, 3, 'float32')); - AHRSCalibration.gyro_tempcompfactor = double(fread(fid, 3, 'float32')); - AHRSCalibration.mag_bias = double(fread(fid, 3, 'float32')); - AHRSCalibration.mag_scale = double(fread(fid, 3, 'float32')); - AHRSCalibration.mag_var = double(fread(fid, 3, 'float32')); - AHRSCalibration.vel_var = double(fread(fid, 1, 'float32')); - AHRSCalibration.pos_var = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [AHRSSettings] = ReadAHRSSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - AHRSSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - AHRSSettings.timestamp = timestamp; - AHRSSettings.Algorithm = double(fread(fid, 1, 'uint8')); - AHRSSettings.Downsampling = double(fread(fid, 1, 'uint8')); - AHRSSettings.UpdatePeriod = double(fread(fid, 1, 'uint8')); - AHRSSettings.BiasCorrectedRaw = double(fread(fid, 1, 'uint8')); - AHRSSettings.YawBias = double(fread(fid, 1, 'float32')); - AHRSSettings.PitchBias = double(fread(fid, 1, 'float32')); - AHRSSettings.RollBias = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [AhrsStatus] = ReadAhrsStatusObject(fid, timestamp) - if 1 - headerSize = 8; - else - AhrsStatus.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - AhrsStatus.timestamp = timestamp; - AhrsStatus.SerialNumber = double(fread(fid, 8, 'uint8')); - AhrsStatus.CPULoad = double(fread(fid, 1, 'uint8')); - AhrsStatus.RunningTime = double(fread(fid, 1, 'uint32')); - AhrsStatus.IdleTimePerCyle = double(fread(fid, 1, 'uint8')); - AhrsStatus.RunningTimePerCyle = double(fread(fid, 1, 'uint8')); - AhrsStatus.DroppedUpdates = double(fread(fid, 1, 'uint8')); - AhrsStatus.LinkRunning = double(fread(fid, 1, 'uint8')); - AhrsStatus.AhrsKickstarts = double(fread(fid, 1, 'uint8')); - AhrsStatus.AhrsCrcErrors = double(fread(fid, 1, 'uint8')); - AhrsStatus.AhrsRetries = double(fread(fid, 1, 'uint8')); - AhrsStatus.AhrsInvalidPackets = double(fread(fid, 1, 'uint8')); - AhrsStatus.OpCrcErrors = double(fread(fid, 1, 'uint8')); - AhrsStatus.OpRetries = double(fread(fid, 1, 'uint8')); - AhrsStatus.OpInvalidPackets = double(fread(fid, 1, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [AttitudeActual] = ReadAttitudeActualObject(fid, timestamp) - if 1 - headerSize = 8; - else - AttitudeActual.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - AttitudeActual.timestamp = timestamp; - AttitudeActual.q1 = double(fread(fid, 1, 'float32')); - AttitudeActual.q2 = double(fread(fid, 1, 'float32')); - AttitudeActual.q3 = double(fread(fid, 1, 'float32')); - AttitudeActual.q4 = double(fread(fid, 1, 'float32')); - AttitudeActual.Roll = double(fread(fid, 1, 'float32')); - AttitudeActual.Pitch = double(fread(fid, 1, 'float32')); - AttitudeActual.Yaw = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [AttitudeDesired] = ReadAttitudeDesiredObject(fid, timestamp) - if 1 - headerSize = 8; - else - AttitudeDesired.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - AttitudeDesired.timestamp = timestamp; - AttitudeDesired.Roll = double(fread(fid, 1, 'float32')); - AttitudeDesired.Pitch = double(fread(fid, 1, 'float32')); - AttitudeDesired.Yaw = double(fread(fid, 1, 'float32')); - AttitudeDesired.Throttle = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [AttitudeRaw] = ReadAttitudeRawObject(fid, timestamp) - if 1 - headerSize = 8; - else - AttitudeRaw.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - AttitudeRaw.timestamp = timestamp; - AttitudeRaw.magnetometers = double(fread(fid, 3, 'int16')); - AttitudeRaw.gyros = double(fread(fid, 3, 'uint16')); - AttitudeRaw.gyros_filtered = double(fread(fid, 3, 'float32')); - AttitudeRaw.gyrotemp = double(fread(fid, 2, 'uint16')); - AttitudeRaw.accels = double(fread(fid, 3, 'uint16')); - AttitudeRaw.accels_filtered = double(fread(fid, 3, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [BaroAltitude] = ReadBaroAltitudeObject(fid, timestamp) - if 1 - headerSize = 8; - else - BaroAltitude.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - BaroAltitude.timestamp = timestamp; - BaroAltitude.Altitude = double(fread(fid, 1, 'float32')); - BaroAltitude.Temperature = double(fread(fid, 1, 'float32')); - BaroAltitude.Pressure = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [BatterySettings] = ReadBatterySettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - BatterySettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - BatterySettings.timestamp = timestamp; - BatterySettings.BatteryVoltage = double(fread(fid, 1, 'float32')); - BatterySettings.BatteryCapacity = double(fread(fid, 1, 'uint32')); - BatterySettings.BatteryType = double(fread(fid, 1, 'uint8')); - BatterySettings.Calibrations = double(fread(fid, 2, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [FirmwareIAPObj] = ReadFirmwareIAPObjObject(fid, timestamp) - if 1 - headerSize = 8; - else - FirmwareIAPObj.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - FirmwareIAPObj.timestamp = timestamp; - FirmwareIAPObj.Command = double(fread(fid, 1, 'uint16')); - FirmwareIAPObj.Description = double(fread(fid, 100, 'uint8')); - FirmwareIAPObj.HWVersion = double(fread(fid, 1, 'uint8')); - FirmwareIAPObj.Target = double(fread(fid, 1, 'uint8')); - FirmwareIAPObj.ArmReset = double(fread(fid, 1, 'uint8')); - FirmwareIAPObj.crc = double(fread(fid, 1, 'uint32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [FlightBatteryState] = ReadFlightBatteryStateObject(fid, timestamp) - if 1 - headerSize = 8; - else - FlightBatteryState.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - FlightBatteryState.timestamp = timestamp; - FlightBatteryState.Voltage = double(fread(fid, 1, 'float32')); - FlightBatteryState.Current = double(fread(fid, 1, 'float32')); - FlightBatteryState.PeakCurrent = double(fread(fid, 1, 'float32')); - FlightBatteryState.AvgCurrent = double(fread(fid, 1, 'float32')); - FlightBatteryState.ConsumedEnergy = double(fread(fid, 1, 'float32')); - FlightBatteryState.EstimatedFlightTime = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [FlightPlanControl] = ReadFlightPlanControlObject(fid, timestamp) - if 1 - headerSize = 8; - else - FlightPlanControl.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - FlightPlanControl.timestamp = timestamp; - FlightPlanControl.Test = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [FlightPlanSettings] = ReadFlightPlanSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - FlightPlanSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - FlightPlanSettings.timestamp = timestamp; - FlightPlanSettings.Test = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [FlightPlanStatus] = ReadFlightPlanStatusObject(fid, timestamp) - if 1 - headerSize = 8; - else - FlightPlanStatus.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - FlightPlanStatus.timestamp = timestamp; - FlightPlanStatus.Status = double(fread(fid, 1, 'uint8')); - FlightPlanStatus.ErrorType = double(fread(fid, 1, 'uint8')); - FlightPlanStatus.ErrorFileID = double(fread(fid, 1, 'uint32')); - FlightPlanStatus.ErrorLineNum = double(fread(fid, 1, 'uint32')); - FlightPlanStatus.Debug = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [FlightTelemetryStats] = ReadFlightTelemetryStatsObject(fid, timestamp) - if 1 - headerSize = 8; - else - FlightTelemetryStats.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - FlightTelemetryStats.timestamp = timestamp; - FlightTelemetryStats.Status = double(fread(fid, 1, 'uint8')); - FlightTelemetryStats.TxDataRate = double(fread(fid, 1, 'float32')); - FlightTelemetryStats.RxDataRate = double(fread(fid, 1, 'float32')); - FlightTelemetryStats.TxFailures = double(fread(fid, 1, 'uint32')); - FlightTelemetryStats.RxFailures = double(fread(fid, 1, 'uint32')); - FlightTelemetryStats.TxRetries = double(fread(fid, 1, 'uint32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [GCSTelemetryStats] = ReadGCSTelemetryStatsObject(fid, timestamp) - if 1 - headerSize = 8; - else - GCSTelemetryStats.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - GCSTelemetryStats.timestamp = timestamp; - GCSTelemetryStats.Status = double(fread(fid, 1, 'uint8')); - GCSTelemetryStats.TxDataRate = double(fread(fid, 1, 'float32')); - GCSTelemetryStats.RxDataRate = double(fread(fid, 1, 'float32')); - GCSTelemetryStats.TxFailures = double(fread(fid, 1, 'uint32')); - GCSTelemetryStats.RxFailures = double(fread(fid, 1, 'uint32')); - GCSTelemetryStats.TxRetries = double(fread(fid, 1, 'uint32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [GPSPosition] = ReadGPSPositionObject(fid, timestamp) - if 1 - headerSize = 8; - else - GPSPosition.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - GPSPosition.timestamp = timestamp; - GPSPosition.Status = double(fread(fid, 1, 'uint8')); - GPSPosition.Latitude = double(fread(fid, 1, 'int32')); - GPSPosition.Longitude = double(fread(fid, 1, 'int32')); - GPSPosition.Altitude = double(fread(fid, 1, 'float32')); - GPSPosition.GeoidSeparation = double(fread(fid, 1, 'float32')); - GPSPosition.Heading = double(fread(fid, 1, 'float32')); - GPSPosition.Groundspeed = double(fread(fid, 1, 'float32')); - GPSPosition.Satellites = double(fread(fid, 1, 'int8')); - GPSPosition.PDOP = double(fread(fid, 1, 'float32')); - GPSPosition.HDOP = double(fread(fid, 1, 'float32')); - GPSPosition.VDOP = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [GPSSatellites] = ReadGPSSatellitesObject(fid, timestamp) - if 1 - headerSize = 8; - else - GPSSatellites.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - GPSSatellites.timestamp = timestamp; - GPSSatellites.SatsInView = double(fread(fid, 1, 'int8')); - GPSSatellites.PRN = double(fread(fid, 16, 'int8')); - GPSSatellites.Elevation = double(fread(fid, 16, 'float32')); - GPSSatellites.Azimuth = double(fread(fid, 16, 'float32')); - GPSSatellites.SNR = double(fread(fid, 16, 'int8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [GPSTime] = ReadGPSTimeObject(fid, timestamp) - if 1 - headerSize = 8; - else - GPSTime.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - GPSTime.timestamp = timestamp; - GPSTime.Month = double(fread(fid, 1, 'int8')); - GPSTime.Day = double(fread(fid, 1, 'int8')); - GPSTime.Year = double(fread(fid, 1, 'int16')); - GPSTime.Hour = double(fread(fid, 1, 'int8')); - GPSTime.Minute = double(fread(fid, 1, 'int8')); - GPSTime.Second = double(fread(fid, 1, 'int8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [GuidanceSettings] = ReadGuidanceSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - GuidanceSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - GuidanceSettings.timestamp = timestamp; - GuidanceSettings.GuidanceMode = double(fread(fid, 1, 'uint8')); - GuidanceSettings.MaxGroundspeed = double(fread(fid, 1, 'int32')); - GuidanceSettings.GroundVelocityP = double(fread(fid, 1, 'float32')); - GuidanceSettings.MaxVerticalSpeed = double(fread(fid, 1, 'int32')); - GuidanceSettings.VertVelocityP = double(fread(fid, 1, 'float32')); - GuidanceSettings.VelP = double(fread(fid, 1, 'float32')); - GuidanceSettings.VelI = double(fread(fid, 1, 'float32')); - GuidanceSettings.VelD = double(fread(fid, 1, 'float32')); - GuidanceSettings.DownP = double(fread(fid, 1, 'float32')); - GuidanceSettings.DownI = double(fread(fid, 1, 'float32')); - GuidanceSettings.DownD = double(fread(fid, 1, 'float32')); - GuidanceSettings.MaxVelIntegral = double(fread(fid, 1, 'float32')); - GuidanceSettings.MaxThrottleIntegral = double(fread(fid, 1, 'float32')); - GuidanceSettings.VelUpdatePeriod = double(fread(fid, 1, 'int32')); - GuidanceSettings.VelPIDUpdatePeriod = double(fread(fid, 1, 'int32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [HomeLocation] = ReadHomeLocationObject(fid, timestamp) - if 1 - headerSize = 8; - else - HomeLocation.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - HomeLocation.timestamp = timestamp; - HomeLocation.Set = double(fread(fid, 1, 'uint8')); - HomeLocation.Latitude = double(fread(fid, 1, 'int32')); - HomeLocation.Longitude = double(fread(fid, 1, 'int32')); - HomeLocation.Altitude = double(fread(fid, 1, 'float32')); - HomeLocation.ECEF = double(fread(fid, 3, 'int32')); - HomeLocation.RNE = double(fread(fid, 9, 'float32')); - HomeLocation.Be = double(fread(fid, 3, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [I2CStats] = ReadI2CStatsObject(fid, timestamp) - if 1 - headerSize = 8; - else - I2CStats.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - I2CStats.timestamp = timestamp; - I2CStats.event_errors = double(fread(fid, 1, 'uint16')); - I2CStats.fsm_errors = double(fread(fid, 1, 'uint16')); - I2CStats.irq_errors = double(fread(fid, 1, 'uint16')); - I2CStats.last_error_type = double(fread(fid, 1, 'uint8')); - I2CStats.evirq_log = double(fread(fid, 5, 'uint32')); - I2CStats.erirq_log = double(fread(fid, 5, 'uint32')); - I2CStats.event_log = double(fread(fid, 5, 'uint8')); - I2CStats.state_log = double(fread(fid, 5, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [ManualControlCommand] = ReadManualControlCommandObject(fid, timestamp) - if 1 - headerSize = 8; - else - ManualControlCommand.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - ManualControlCommand.timestamp = timestamp; - ManualControlCommand.Connected = double(fread(fid, 1, 'uint8')); - ManualControlCommand.Armed = double(fread(fid, 1, 'uint8')); - ManualControlCommand.Roll = double(fread(fid, 1, 'float32')); - ManualControlCommand.Pitch = double(fread(fid, 1, 'float32')); - ManualControlCommand.Yaw = double(fread(fid, 1, 'float32')); - ManualControlCommand.Throttle = double(fread(fid, 1, 'float32')); - ManualControlCommand.FlightMode = double(fread(fid, 1, 'uint8')); - ManualControlCommand.StabilizationSettings = double(fread(fid, 3, 'uint8')); - ManualControlCommand.Accessory1 = double(fread(fid, 1, 'float32')); - ManualControlCommand.Accessory2 = double(fread(fid, 1, 'float32')); - ManualControlCommand.Accessory3 = double(fread(fid, 1, 'float32')); - ManualControlCommand.Channel = double(fread(fid, 8, 'int16')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [ManualControlSettings] = ReadManualControlSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - ManualControlSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - ManualControlSettings.timestamp = timestamp; - ManualControlSettings.InputMode = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Roll = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Pitch = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Yaw = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Throttle = double(fread(fid, 1, 'uint8')); - ManualControlSettings.FlightMode = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Accessory1 = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Accessory2 = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Accessory3 = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Pos1StabilizationSettings = double(fread(fid, 3, 'uint8')); - ManualControlSettings.Pos2StabilizationSettings = double(fread(fid, 3, 'uint8')); - ManualControlSettings.Pos3StabilizationSettings = double(fread(fid, 3, 'uint8')); - ManualControlSettings.Pos1FlightMode = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Pos2FlightMode = double(fread(fid, 1, 'uint8')); - ManualControlSettings.Pos3FlightMode = double(fread(fid, 1, 'uint8')); - ManualControlSettings.ChannelMax = double(fread(fid, 8, 'int16')); - ManualControlSettings.ChannelNeutral = double(fread(fid, 8, 'int16')); - ManualControlSettings.ChannelMin = double(fread(fid, 8, 'int16')); - ManualControlSettings.ArmedTimeout = double(fread(fid, 1, 'uint16')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [MixerSettings] = ReadMixerSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - MixerSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - MixerSettings.timestamp = timestamp; - MixerSettings.MaxAccel = double(fread(fid, 1, 'float32')); - MixerSettings.FeedForward = double(fread(fid, 1, 'float32')); - MixerSettings.AccelTime = double(fread(fid, 1, 'float32')); - MixerSettings.DecelTime = double(fread(fid, 1, 'float32')); - MixerSettings.ThrottleCurve1 = double(fread(fid, 5, 'float32')); - MixerSettings.ThrottleCurve2 = double(fread(fid, 5, 'float32')); - MixerSettings.Mixer1Type = double(fread(fid, 1, 'uint8')); - MixerSettings.Mixer1Vector = double(fread(fid, 5, 'int8')); - MixerSettings.Mixer2Type = double(fread(fid, 1, 'uint8')); - MixerSettings.Mixer2Vector = double(fread(fid, 5, 'int8')); - MixerSettings.Mixer3Type = double(fread(fid, 1, 'uint8')); - MixerSettings.Mixer3Vector = double(fread(fid, 5, 'int8')); - MixerSettings.Mixer4Type = double(fread(fid, 1, 'uint8')); - MixerSettings.Mixer4Vector = double(fread(fid, 5, 'int8')); - MixerSettings.Mixer5Type = double(fread(fid, 1, 'uint8')); - MixerSettings.Mixer5Vector = double(fread(fid, 5, 'int8')); - MixerSettings.Mixer6Type = double(fread(fid, 1, 'uint8')); - MixerSettings.Mixer6Vector = double(fread(fid, 5, 'int8')); - MixerSettings.Mixer7Type = double(fread(fid, 1, 'uint8')); - MixerSettings.Mixer7Vector = double(fread(fid, 5, 'int8')); - MixerSettings.Mixer8Type = double(fread(fid, 1, 'uint8')); - MixerSettings.Mixer8Vector = double(fread(fid, 5, 'int8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [MixerStatus] = ReadMixerStatusObject(fid, timestamp) - if 1 - headerSize = 8; - else - MixerStatus.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - MixerStatus.timestamp = timestamp; - MixerStatus.Mixer1 = double(fread(fid, 1, 'float32')); - MixerStatus.Mixer2 = double(fread(fid, 1, 'float32')); - MixerStatus.Mixer3 = double(fread(fid, 1, 'float32')); - MixerStatus.Mixer4 = double(fread(fid, 1, 'float32')); - MixerStatus.Mixer5 = double(fread(fid, 1, 'float32')); - MixerStatus.Mixer6 = double(fread(fid, 1, 'float32')); - MixerStatus.Mixer7 = double(fread(fid, 1, 'float32')); - MixerStatus.Mixer8 = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [ObjectPersistence] = ReadObjectPersistenceObject(fid, timestamp) - if 1 - headerSize = 8; - else - ObjectPersistence.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - ObjectPersistence.timestamp = timestamp; - ObjectPersistence.Operation = double(fread(fid, 1, 'uint8')); - ObjectPersistence.Selection = double(fread(fid, 1, 'uint8')); - ObjectPersistence.ObjectID = double(fread(fid, 1, 'uint32')); - ObjectPersistence.InstanceID = double(fread(fid, 1, 'uint32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [PipXtremeModemSettings] = ReadPipXtremeModemSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - PipXtremeModemSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - PipXtremeModemSettings.timestamp = timestamp; - PipXtremeModemSettings.Mode = double(fread(fid, 1, 'uint8')); - PipXtremeModemSettings.Serial_Baudrate = double(fread(fid, 1, 'uint8')); - PipXtremeModemSettings.Frequency_Calibration = double(fread(fid, 1, 'uint8')); - PipXtremeModemSettings.Frequency_Min = double(fread(fid, 1, 'uint32')); - PipXtremeModemSettings.Frequency_Max = double(fread(fid, 1, 'uint32')); - PipXtremeModemSettings.Frequency = double(fread(fid, 1, 'uint32')); - PipXtremeModemSettings.Max_RF_Bandwidth = double(fread(fid, 1, 'uint8')); - PipXtremeModemSettings.Max_Tx_Power = double(fread(fid, 1, 'uint8')); - PipXtremeModemSettings.Tx_Data_Wait = double(fread(fid, 1, 'uint8')); - PipXtremeModemSettings.AES_Encryption = double(fread(fid, 1, 'uint8')); - PipXtremeModemSettings.AES_EncryptionKey = double(fread(fid, 16, 'uint8')); - PipXtremeModemSettings.Paired_Serial_Number = double(fread(fid, 1, 'uint32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [PipXtremeModemStatus] = ReadPipXtremeModemStatusObject(fid, timestamp) - if 1 - headerSize = 8; - else - PipXtremeModemStatus.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - PipXtremeModemStatus.timestamp = timestamp; - PipXtremeModemStatus.Firmware_Version_Major = double(fread(fid, 1, 'uint8')); - PipXtremeModemStatus.Firmware_Version_Minor = double(fread(fid, 1, 'uint8')); - PipXtremeModemStatus.Serial_Number = double(fread(fid, 1, 'uint32')); - PipXtremeModemStatus.Up_Time = double(fread(fid, 1, 'uint32')); - PipXtremeModemStatus.Frequency = double(fread(fid, 1, 'uint32')); - PipXtremeModemStatus.RF_Bandwidth = double(fread(fid, 1, 'uint32')); - PipXtremeModemStatus.Tx_Power = double(fread(fid, 1, 'int8')); - PipXtremeModemStatus.State = double(fread(fid, 1, 'uint8')); - PipXtremeModemStatus.Tx_Retry = double(fread(fid, 1, 'uint16')); - PipXtremeModemStatus.Tx_Data_Rate = double(fread(fid, 1, 'uint32')); - PipXtremeModemStatus.Rx_Data_Rate = double(fread(fid, 1, 'uint32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [PositionActual] = ReadPositionActualObject(fid, timestamp) - if 1 - headerSize = 8; - else - PositionActual.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - PositionActual.timestamp = timestamp; - PositionActual.North = double(fread(fid, 1, 'int32')); - PositionActual.East = double(fread(fid, 1, 'int32')); - PositionActual.Down = double(fread(fid, 1, 'int32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [PositionDesired] = ReadPositionDesiredObject(fid, timestamp) - if 1 - headerSize = 8; - else - PositionDesired.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - PositionDesired.timestamp = timestamp; - PositionDesired.North = double(fread(fid, 1, 'int32')); - PositionDesired.East = double(fread(fid, 1, 'int32')); - PositionDesired.Down = double(fread(fid, 1, 'int32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [RateDesired] = ReadRateDesiredObject(fid, timestamp) - if 1 - headerSize = 8; - else - RateDesired.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - RateDesired.timestamp = timestamp; - RateDesired.Roll = double(fread(fid, 1, 'float32')); - RateDesired.Pitch = double(fread(fid, 1, 'float32')); - RateDesired.Yaw = double(fread(fid, 1, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [StabilizationSettings] = ReadStabilizationSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - StabilizationSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - StabilizationSettings.timestamp = timestamp; - StabilizationSettings.RollMax = double(fread(fid, 1, 'uint8')); - StabilizationSettings.PitchMax = double(fread(fid, 1, 'uint8')); - StabilizationSettings.YawMax = double(fread(fid, 1, 'uint8')); - StabilizationSettings.ManualRate = double(fread(fid, 3, 'float32')); - StabilizationSettings.MaximumRate = double(fread(fid, 3, 'float32')); - StabilizationSettings.RollRatePI = double(fread(fid, 3, 'float32')); - StabilizationSettings.PitchRatePI = double(fread(fid, 3, 'float32')); - StabilizationSettings.YawRatePI = double(fread(fid, 3, 'float32')); - StabilizationSettings.RollPI = double(fread(fid, 3, 'float32')); - StabilizationSettings.PitchPI = double(fread(fid, 3, 'float32')); - StabilizationSettings.YawPI = double(fread(fid, 3, 'float32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [SystemAlarms] = ReadSystemAlarmsObject(fid, timestamp) - if 1 - headerSize = 8; - else - SystemAlarms.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - SystemAlarms.timestamp = timestamp; - SystemAlarms.Alarm = double(fread(fid, 14, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [SystemSettings] = ReadSystemSettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - SystemSettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - SystemSettings.timestamp = timestamp; - SystemSettings.AirframeType = double(fread(fid, 1, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [SystemStats] = ReadSystemStatsObject(fid, timestamp) - if 1 - headerSize = 8; - else - SystemStats.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - SystemStats.timestamp = timestamp; - SystemStats.FlightTime = double(fread(fid, 1, 'uint32')); - SystemStats.HeapRemaining = double(fread(fid, 1, 'uint16')); - SystemStats.CPULoad = double(fread(fid, 1, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [TaskInfo] = ReadTaskInfoObject(fid, timestamp) - if 1 - headerSize = 8; - else - TaskInfo.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - TaskInfo.timestamp = timestamp; - TaskInfo.StackRemaining = double(fread(fid, 13, 'uint16')); - TaskInfo.Running = double(fread(fid, 13, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [TelemetrySettings] = ReadTelemetrySettingsObject(fid, timestamp) - if 1 - headerSize = 8; - else - TelemetrySettings.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - TelemetrySettings.timestamp = timestamp; - TelemetrySettings.Speed = double(fread(fid, 1, 'uint8')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [VelocityActual] = ReadVelocityActualObject(fid, timestamp) - if 1 - headerSize = 8; - else - VelocityActual.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - VelocityActual.timestamp = timestamp; - VelocityActual.North = double(fread(fid, 1, 'int32')); - VelocityActual.East = double(fread(fid, 1, 'int32')); - VelocityActual.Down = double(fread(fid, 1, 'int32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [VelocityDesired] = ReadVelocityDesiredObject(fid, timestamp) - if 1 - headerSize = 8; - else - VelocityDesired.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - VelocityDesired.timestamp = timestamp; - VelocityDesired.North = double(fread(fid, 1, 'int32')); - VelocityDesired.East = double(fread(fid, 1, 'int32')); - VelocityDesired.Down = double(fread(fid, 1, 'int32')); - % read CRC - fread(fid, 1, 'uint8'); -end - -function [WatchdogStatus] = ReadWatchdogStatusObject(fid, timestamp) - if 1 - headerSize = 8; - else - WatchdogStatus.instanceID = fread(fid, 1, 'uint16'); - headerSize = 10; - end - - WatchdogStatus.timestamp = timestamp; - WatchdogStatus.BootupFlags = double(fread(fid, 1, 'uint16')); - WatchdogStatus.ActiveFlags = double(fread(fid, 1, 'uint16')); - % read CRC - fread(fid, 1, 'uint8'); -end - - - - diff --git a/ground/src/plugins/uavobjects/actuatorcommand.py b/ground/src/plugins/uavobjects/actuatorcommand.py deleted file mode 100644 index 3b9b546c0..000000000 --- a/ground/src/plugins/uavobjects/actuatorcommand.py +++ /dev/null @@ -1,123 +0,0 @@ -## -############################################################################## -# -# @file actuatorcommand.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the ActuatorCommand object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: actuatorcommand.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Channel', - 'h', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), - uavobject.UAVObjectField( - 'UpdateTime', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'MaxUpdateTime', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'NumFailedUpdates', - 'B', - 1, - [ - '0', - ], - { - } - ), -] - - -class ActuatorCommand(uavobject.UAVObject): - ## Object constants - OBJID = 3907024856 - NAME = "ActuatorCommand" - METANAME = "ActuatorCommandMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = ActuatorCommand() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/actuatordesired.py b/ground/src/plugins/uavobjects/actuatordesired.py deleted file mode 100644 index a081a6be5..000000000 --- a/ground/src/plugins/uavobjects/actuatordesired.py +++ /dev/null @@ -1,136 +0,0 @@ -## -############################################################################## -# -# @file actuatordesired.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the ActuatorDesired object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: actuatordesired.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Roll', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Pitch', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Yaw', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Throttle', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'UpdateTime', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'NumLongUpdates', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class ActuatorDesired(uavobject.UAVObject): - ## Object constants - OBJID = 3562104706 - NAME = "ActuatorDesired" - METANAME = "ActuatorDesiredMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = ActuatorDesired() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/actuatorsettings.py b/ground/src/plugins/uavobjects/actuatorsettings.py deleted file mode 100644 index bfc9ff825..000000000 --- a/ground/src/plugins/uavobjects/actuatorsettings.py +++ /dev/null @@ -1,441 +0,0 @@ -## -############################################################################## -# -# @file actuatorsettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the ActuatorSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: actuatorsettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'FixedWingRoll1', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'FixedWingRoll2', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'FixedWingPitch1', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'FixedWingPitch2', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'FixedWingYaw', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'FixedWingThrottle', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'VTOLMotorN', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'VTOLMotorNE', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'VTOLMotorE', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'VTOLMotorSE', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'VTOLMotorS', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'VTOLMotorSW', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'VTOLMotorW', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'VTOLMotorNW', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'ChannelUpdateFreq', - 'h', - 2, - [ - '0', - '1', - ], - { - } - ), - uavobject.UAVObjectField( - 'ChannelMax', - 'h', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), - uavobject.UAVObjectField( - 'ChannelNeutral', - 'h', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), - uavobject.UAVObjectField( - 'ChannelMin', - 'h', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), - uavobject.UAVObjectField( - 'ChannelType', - 'b', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - '0' : 'PWM', - '1' : 'MK', - '2' : 'ASTEC4', - } - ), - uavobject.UAVObjectField( - 'ChannelAddr', - 'B', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), -] - - -class ActuatorSettings(uavobject.UAVObject): - ## Object constants - OBJID = 844831578 - NAME = "ActuatorSettings" - METANAME = "ActuatorSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = ActuatorSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/ahrscalibration.py b/ground/src/plugins/uavobjects/ahrscalibration.py deleted file mode 100644 index e2bccce4a..000000000 --- a/ground/src/plugins/uavobjects/ahrscalibration.py +++ /dev/null @@ -1,228 +0,0 @@ -## -############################################################################## -# -# @file ahrscalibration.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the AHRSCalibration object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: ahrscalibration.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'measure_var', - 'b', - 1, - [ - '0', - ], - { - '0' : 'SET', - '1' : 'MEASURE', - } - ), - uavobject.UAVObjectField( - 'accel_bias', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'accel_scale', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'accel_var', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'gyro_bias', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'gyro_scale', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'gyro_var', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'gyro_tempcompfactor', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'mag_bias', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'mag_scale', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'mag_var', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'vel_var', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'pos_var', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class AHRSCalibration(uavobject.UAVObject): - ## Object constants - OBJID = 806362034 - NAME = "AHRSCalibration" - METANAME = "AHRSCalibrationMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = AHRSCalibration() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/ahrssettings.py b/ground/src/plugins/uavobjects/ahrssettings.py deleted file mode 100644 index a1ca3367b..000000000 --- a/ground/src/plugins/uavobjects/ahrssettings.py +++ /dev/null @@ -1,152 +0,0 @@ -## -############################################################################## -# -# @file ahrssettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the AHRSSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: ahrssettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Algorithm', - 'b', - 1, - [ - '0', - ], - { - '0' : 'SIMPLE', - '1' : 'INSGPS_INDOOR_NOMAG', - '2' : 'INSGPS_INDOOR', - '3' : 'INSGPS_OUTDOOR', - } - ), - uavobject.UAVObjectField( - 'Downsampling', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'UpdatePeriod', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'BiasCorrectedRaw', - 'b', - 1, - [ - '0', - ], - { - '0' : 'TRUE', - '1' : 'FALSE', - } - ), - uavobject.UAVObjectField( - 'YawBias', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'PitchBias', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'RollBias', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class AHRSSettings(uavobject.UAVObject): - ## Object constants - OBJID = 3741078856 - NAME = "AHRSSettings" - METANAME = "AHRSSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = AHRSSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/ahrsstatus.py b/ground/src/plugins/uavobjects/ahrsstatus.py deleted file mode 100644 index dbfc8be91..000000000 --- a/ground/src/plugins/uavobjects/ahrsstatus.py +++ /dev/null @@ -1,225 +0,0 @@ -## -############################################################################## -# -# @file ahrsstatus.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the AhrsStatus object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: ahrsstatus.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'SerialNumber', - 'B', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), - uavobject.UAVObjectField( - 'CPULoad', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'RunningTime', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'IdleTimePerCyle', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'RunningTimePerCyle', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'DroppedUpdates', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'LinkRunning', - 'b', - 1, - [ - '0', - ], - { - '0' : 'FALSE', - '1' : 'TRUE', - } - ), - uavobject.UAVObjectField( - 'AhrsKickstarts', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'AhrsCrcErrors', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'AhrsRetries', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'AhrsInvalidPackets', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'OpCrcErrors', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'OpRetries', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'OpInvalidPackets', - 'B', - 1, - [ - '0', - ], - { - } - ), -] - - -class AhrsStatus(uavobject.UAVObject): - ## Object constants - OBJID = 933623714 - NAME = "AhrsStatus" - METANAME = "AhrsStatusMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = AhrsStatus() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/attitudeactual.py b/ground/src/plugins/uavobjects/attitudeactual.py deleted file mode 100644 index d265c059b..000000000 --- a/ground/src/plugins/uavobjects/attitudeactual.py +++ /dev/null @@ -1,146 +0,0 @@ -## -############################################################################## -# -# @file attitudeactual.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the AttitudeActual object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: attitudeactual.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'q1', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'q2', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'q3', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'q4', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Roll', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Pitch', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Yaw', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class AttitudeActual(uavobject.UAVObject): - ## Object constants - OBJID = 4233858292 - NAME = "AttitudeActual" - METANAME = "AttitudeActualMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = AttitudeActual() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/attitudedesired.py b/ground/src/plugins/uavobjects/attitudedesired.py deleted file mode 100644 index 7eda04377..000000000 --- a/ground/src/plugins/uavobjects/attitudedesired.py +++ /dev/null @@ -1,116 +0,0 @@ -## -############################################################################## -# -# @file attitudedesired.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the AttitudeDesired object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: attitudedesired.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Roll', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Pitch', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Yaw', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Throttle', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class AttitudeDesired(uavobject.UAVObject): - ## Object constants - OBJID = 1412270808 - NAME = "AttitudeDesired" - METANAME = "AttitudeDesiredMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = AttitudeDesired() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/attituderaw.py b/ground/src/plugins/uavobjects/attituderaw.py deleted file mode 100644 index 8dab5c96c..000000000 --- a/ground/src/plugins/uavobjects/attituderaw.py +++ /dev/null @@ -1,147 +0,0 @@ -## -############################################################################## -# -# @file attituderaw.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the AttitudeRaw object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: attituderaw.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'magnetometers', - 'h', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'gyros', - 'H', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'gyros_filtered', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'gyrotemp', - 'H', - 2, - [ - 'XY', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'accels', - 'H', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), - uavobject.UAVObjectField( - 'accels_filtered', - 'f', - 3, - [ - 'X', - 'Y', - 'Z', - ], - { - } - ), -] - - -class AttitudeRaw(uavobject.UAVObject): - ## Object constants - OBJID = 1323193976 - NAME = "AttitudeRaw" - METANAME = "AttitudeRawMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = AttitudeRaw() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/baroaltitude.py b/ground/src/plugins/uavobjects/baroaltitude.py deleted file mode 100644 index 837e074b8..000000000 --- a/ground/src/plugins/uavobjects/baroaltitude.py +++ /dev/null @@ -1,106 +0,0 @@ -## -############################################################################## -# -# @file baroaltitude.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the BaroAltitude object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: baroaltitude.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Altitude', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Temperature', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Pressure', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class BaroAltitude(uavobject.UAVObject): - ## Object constants - OBJID = 3980666102 - NAME = "BaroAltitude" - METANAME = "BaroAltitudeMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = BaroAltitude() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/batterysettings.py b/ground/src/plugins/uavobjects/batterysettings.py deleted file mode 100644 index 287ae60b2..000000000 --- a/ground/src/plugins/uavobjects/batterysettings.py +++ /dev/null @@ -1,122 +0,0 @@ -## -############################################################################## -# -# @file batterysettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the BatterySettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: batterysettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'BatteryVoltage', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'BatteryCapacity', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'BatteryType', - 'b', - 1, - [ - '0', - ], - { - '0' : 'LiPo', - '1' : 'A123', - '2' : 'LiCo', - '3' : 'LiFeSO4', - '4' : 'None', - } - ), - uavobject.UAVObjectField( - 'Calibrations', - 'f', - 2, - [ - 'Voltage', - 'Current', - ], - { - } - ), -] - - -class BatterySettings(uavobject.UAVObject): - ## Object constants - OBJID = 2784959898 - NAME = "BatterySettings" - METANAME = "BatterySettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = BatterySettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/firmwareiapobj.py b/ground/src/plugins/uavobjects/firmwareiapobj.py deleted file mode 100644 index ad22d2461..000000000 --- a/ground/src/plugins/uavobjects/firmwareiapobj.py +++ /dev/null @@ -1,235 +0,0 @@ -## -############################################################################## -# -# @file firmwareiapobj.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the FirmwareIAPObj object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: firmwareiap.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Command', - 'H', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Description', - 'B', - 100, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - '8', - '9', - '10', - '11', - '12', - '13', - '14', - '15', - '16', - '17', - '18', - '19', - '20', - '21', - '22', - '23', - '24', - '25', - '26', - '27', - '28', - '29', - '30', - '31', - '32', - '33', - '34', - '35', - '36', - '37', - '38', - '39', - '40', - '41', - '42', - '43', - '44', - '45', - '46', - '47', - '48', - '49', - '50', - '51', - '52', - '53', - '54', - '55', - '56', - '57', - '58', - '59', - '60', - '61', - '62', - '63', - '64', - '65', - '66', - '67', - '68', - '69', - '70', - '71', - '72', - '73', - '74', - '75', - '76', - '77', - '78', - '79', - '80', - '81', - '82', - '83', - '84', - '85', - '86', - '87', - '88', - '89', - '90', - '91', - '92', - '93', - '94', - '95', - '96', - '97', - '98', - '99', - ], - { - } - ), - uavobject.UAVObjectField( - 'HWVersion', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Target', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'ArmReset', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'crc', - 'I', - 1, - [ - '0', - ], - { - } - ), -] - - -class FirmwareIAPObj(uavobject.UAVObject): - ## Object constants - OBJID = 879185696 - NAME = "FirmwareIAPObj" - METANAME = "FirmwareIAPObjMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = FirmwareIAPObj() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/flightbatterystate.py b/ground/src/plugins/uavobjects/flightbatterystate.py deleted file mode 100644 index f08e67f7c..000000000 --- a/ground/src/plugins/uavobjects/flightbatterystate.py +++ /dev/null @@ -1,136 +0,0 @@ -## -############################################################################## -# -# @file flightbatterystate.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the FlightBatteryState object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: flightbatterystate.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Voltage', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Current', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'PeakCurrent', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'AvgCurrent', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'ConsumedEnergy', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'EstimatedFlightTime', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class FlightBatteryState(uavobject.UAVObject): - ## Object constants - OBJID = 126985486 - NAME = "FlightBatteryState" - METANAME = "FlightBatteryStateMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = FlightBatteryState() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/flightplancontrol.py b/ground/src/plugins/uavobjects/flightplancontrol.py deleted file mode 100644 index f0d9556ce..000000000 --- a/ground/src/plugins/uavobjects/flightplancontrol.py +++ /dev/null @@ -1,86 +0,0 @@ -## -############################################################################## -# -# @file flightplancontrol.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the FlightPlanControl object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: flightplancontrol.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Test', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class FlightPlanControl(uavobject.UAVObject): - ## Object constants - OBJID = 4125349796 - NAME = "FlightPlanControl" - METANAME = "FlightPlanControlMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = FlightPlanControl() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/flightplansettings.py b/ground/src/plugins/uavobjects/flightplansettings.py deleted file mode 100644 index 0ce7898e3..000000000 --- a/ground/src/plugins/uavobjects/flightplansettings.py +++ /dev/null @@ -1,86 +0,0 @@ -## -############################################################################## -# -# @file flightplansettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the FlightPlanSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: flightplansettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Test', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class FlightPlanSettings(uavobject.UAVObject): - ## Object constants - OBJID = 2234942498 - NAME = "FlightPlanSettings" - METANAME = "FlightPlanSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = FlightPlanSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/flightplanstatus.py b/ground/src/plugins/uavobjects/flightplanstatus.py deleted file mode 100644 index dc92e8626..000000000 --- a/ground/src/plugins/uavobjects/flightplanstatus.py +++ /dev/null @@ -1,133 +0,0 @@ -## -############################################################################## -# -# @file flightplanstatus.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the FlightPlanStatus object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: flightplanstatus.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Status', - 'b', - 1, - [ - '0', - ], - { - '0' : 'None', - '1' : 'Running', - '2' : 'Idle', - '3' : 'VMInitError', - '4' : 'ScriptStartError', - '5' : 'RunTimeError', - } - ), - uavobject.UAVObjectField( - 'ErrorType', - 'b', - 1, - [ - '0', - ], - { - '0' : 'None', - } - ), - uavobject.UAVObjectField( - 'ErrorFileID', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'ErrorLineNum', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Debug', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class FlightPlanStatus(uavobject.UAVObject): - ## Object constants - OBJID = 2726772894 - NAME = "FlightPlanStatus" - METANAME = "FlightPlanStatusMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = FlightPlanStatus() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/flighttelemetrystats.py b/ground/src/plugins/uavobjects/flighttelemetrystats.py deleted file mode 100644 index c7beab034..000000000 --- a/ground/src/plugins/uavobjects/flighttelemetrystats.py +++ /dev/null @@ -1,140 +0,0 @@ -## -############################################################################## -# -# @file flighttelemetrystats.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the FlightTelemetryStats object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: flighttelemetrystats.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Status', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disconnected', - '1' : 'HandshakeReq', - '2' : 'HandshakeAck', - '3' : 'Connected', - } - ), - uavobject.UAVObjectField( - 'TxDataRate', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'RxDataRate', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'TxFailures', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'RxFailures', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'TxRetries', - 'I', - 1, - [ - '0', - ], - { - } - ), -] - - -class FlightTelemetryStats(uavobject.UAVObject): - ## Object constants - OBJID = 1712072286 - NAME = "FlightTelemetryStats" - METANAME = "FlightTelemetryStatsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = FlightTelemetryStats() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/gcstelemetrystats.py b/ground/src/plugins/uavobjects/gcstelemetrystats.py deleted file mode 100644 index dbe13944e..000000000 --- a/ground/src/plugins/uavobjects/gcstelemetrystats.py +++ /dev/null @@ -1,140 +0,0 @@ -## -############################################################################## -# -# @file gcstelemetrystats.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the GCSTelemetryStats object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: gcstelemetrystats.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Status', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disconnected', - '1' : 'HandshakeReq', - '2' : 'HandshakeAck', - '3' : 'Connected', - } - ), - uavobject.UAVObjectField( - 'TxDataRate', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'RxDataRate', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'TxFailures', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'RxFailures', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'TxRetries', - 'I', - 1, - [ - '0', - ], - { - } - ), -] - - -class GCSTelemetryStats(uavobject.UAVObject): - ## Object constants - OBJID = 1998458950 - NAME = "GCSTelemetryStats" - METANAME = "GCSTelemetryStatsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = GCSTelemetryStats() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/gpsposition.py b/ground/src/plugins/uavobjects/gpsposition.py deleted file mode 100644 index d49a88ff1..000000000 --- a/ground/src/plugins/uavobjects/gpsposition.py +++ /dev/null @@ -1,190 +0,0 @@ -## -############################################################################## -# -# @file gpsposition.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the GPSPosition object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: gpsposition.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Status', - 'b', - 1, - [ - '0', - ], - { - '0' : 'NoGPS', - '1' : 'NoFix', - '2' : 'Fix2D', - '3' : 'Fix3D', - } - ), - uavobject.UAVObjectField( - 'Latitude', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Longitude', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Altitude', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'GeoidSeparation', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Heading', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Groundspeed', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Satellites', - 'b', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'PDOP', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'HDOP', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'VDOP', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class GPSPosition(uavobject.UAVObject): - ## Object constants - OBJID = 3041480770 - NAME = "GPSPosition" - METANAME = "GPSPositionMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = GPSPosition() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/gpssatellites.py b/ground/src/plugins/uavobjects/gpssatellites.py deleted file mode 100644 index f343a5cf0..000000000 --- a/ground/src/plugins/uavobjects/gpssatellites.py +++ /dev/null @@ -1,186 +0,0 @@ -## -############################################################################## -# -# @file gpssatellites.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the GPSSatellites object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: gpssatellites.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'SatsInView', - 'b', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'PRN', - 'b', - 16, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - '8', - '9', - '10', - '11', - '12', - '13', - '14', - '15', - ], - { - } - ), - uavobject.UAVObjectField( - 'Elevation', - 'f', - 16, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - '8', - '9', - '10', - '11', - '12', - '13', - '14', - '15', - ], - { - } - ), - uavobject.UAVObjectField( - 'Azimuth', - 'f', - 16, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - '8', - '9', - '10', - '11', - '12', - '13', - '14', - '15', - ], - { - } - ), - uavobject.UAVObjectField( - 'SNR', - 'b', - 16, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - '8', - '9', - '10', - '11', - '12', - '13', - '14', - '15', - ], - { - } - ), -] - - -class GPSSatellites(uavobject.UAVObject): - ## Object constants - OBJID = 3593446318 - NAME = "GPSSatellites" - METANAME = "GPSSatellitesMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = GPSSatellites() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/gpstime.py b/ground/src/plugins/uavobjects/gpstime.py deleted file mode 100644 index 1cec36a90..000000000 --- a/ground/src/plugins/uavobjects/gpstime.py +++ /dev/null @@ -1,136 +0,0 @@ -## -############################################################################## -# -# @file gpstime.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the GPSTime object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: gpstime.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Month', - 'b', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Day', - 'b', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Year', - 'h', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Hour', - 'b', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Minute', - 'b', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Second', - 'b', - 1, - [ - '0', - ], - { - } - ), -] - - -class GPSTime(uavobject.UAVObject): - ## Object constants - OBJID = 1459613858 - NAME = "GPSTime" - METANAME = "GPSTimeMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = GPSTime() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/guidancesettings.py b/ground/src/plugins/uavobjects/guidancesettings.py deleted file mode 100644 index b0bf662c5..000000000 --- a/ground/src/plugins/uavobjects/guidancesettings.py +++ /dev/null @@ -1,229 +0,0 @@ -## -############################################################################## -# -# @file guidancesettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the GuidanceSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: guidancesettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'GuidanceMode', - 'b', - 1, - [ - '0', - ], - { - '0' : 'DUAL_LOOP', - '1' : 'VELOCITY_CONTROL', - '2' : 'POSITION_PID', - } - ), - uavobject.UAVObjectField( - 'MaxGroundspeed', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'GroundVelocityP', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'MaxVerticalSpeed', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'VertVelocityP', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'VelP', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'VelI', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'VelD', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'DownP', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'DownI', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'DownD', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'MaxVelIntegral', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'MaxThrottleIntegral', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'VelUpdatePeriod', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'VelPIDUpdatePeriod', - 'i', - 1, - [ - '0', - ], - { - } - ), -] - - -class GuidanceSettings(uavobject.UAVObject): - ## Object constants - OBJID = 2071403670 - NAME = "GuidanceSettings" - METANAME = "GuidanceSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = GuidanceSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/homelocation.py b/ground/src/plugins/uavobjects/homelocation.py deleted file mode 100644 index 6de803981..000000000 --- a/ground/src/plugins/uavobjects/homelocation.py +++ /dev/null @@ -1,160 +0,0 @@ -## -############################################################################## -# -# @file homelocation.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the HomeLocation object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: homelocation.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Set', - 'b', - 1, - [ - '0', - ], - { - '0' : 'FALSE', - '1' : 'TRUE', - } - ), - uavobject.UAVObjectField( - 'Latitude', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Longitude', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Altitude', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'ECEF', - 'i', - 3, - [ - '0', - '1', - '2', - ], - { - } - ), - uavobject.UAVObjectField( - 'RNE', - 'f', - 9, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - '8', - ], - { - } - ), - uavobject.UAVObjectField( - 'Be', - 'f', - 3, - [ - '0', - '1', - '2', - ], - { - } - ), -] - - -class HomeLocation(uavobject.UAVObject): - ## Object constants - OBJID = 3590360786 - NAME = "HomeLocation" - METANAME = "HomeLocationMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = HomeLocation() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/i2cstats.py b/ground/src/plugins/uavobjects/i2cstats.py deleted file mode 100644 index 9cf7238f2..000000000 --- a/ground/src/plugins/uavobjects/i2cstats.py +++ /dev/null @@ -1,216 +0,0 @@ -## -############################################################################## -# -# @file i2cstats.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the I2CStats object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: i2cstats.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'event_errors', - 'H', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'fsm_errors', - 'H', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'irq_errors', - 'H', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'last_error_type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'EVENT', - '1' : 'FSM', - '2' : 'INTERRUPT', - } - ), - uavobject.UAVObjectField( - 'evirq_log', - 'I', - 5, - [ - '0', - '1', - '2', - '3', - '4', - ], - { - } - ), - uavobject.UAVObjectField( - 'erirq_log', - 'I', - 5, - [ - '0', - '1', - '2', - '3', - '4', - ], - { - } - ), - uavobject.UAVObjectField( - 'event_log', - 'b', - 5, - [ - '0', - '1', - '2', - '3', - '4', - ], - { - '0' : 'I2C_EVENT_BUS_ERROR', - '1' : 'I2C_EVENT_START', - '2' : 'I2C_EVENT_STARTED_MORE_TXN_READ', - '3' : 'I2C_EVENT_STARTED_MORE_TXN_WRITE', - '4' : 'I2C_EVENT_STARTED_LAST_TXN_READ', - '5' : 'I2C_EVENT_STARTED_LAST_TXN_WRITE', - '6' : 'I2C_EVENT_ADDR_SENT_LEN_EQ_0', - '7' : 'I2C_EVENT_ADDR_SENT_LEN_EQ_1', - '8' : 'I2C_EVENT_ADDR_SENT_LEN_EQ_2', - '9' : 'I2C_EVENT_ADDR_SENT_LEN_GT_2', - '10' : 'I2C_EVENT_TRANSFER_DONE_LEN_EQ_0', - '11' : 'I2C_EVENT_TRANSFER_DONE_LEN_EQ_1', - '12' : 'I2C_EVENT_TRANSFER_DONE_LEN_EQ_2', - '13' : 'I2C_EVENT_TRANSFER_DONE_LEN_GT_2', - '14' : 'I2C_EVENT_NACK', - '15' : 'I2C_EVENT_STOPPED', - '16' : 'I2C_EVENT_AUTO', - } - ), - uavobject.UAVObjectField( - 'state_log', - 'b', - 5, - [ - '0', - '1', - '2', - '3', - '4', - ], - { - '0' : 'I2C_STATE_FSM_FAULT', - '1' : 'I2C_STATE_BUS_ERROR', - '2' : 'I2C_STATE_STOPPED', - '3' : 'I2C_STATE_STOPPING', - '4' : 'I2C_STATE_STARTING', - '5' : 'I2C_STATE_R_MORE_TXN_ADDR', - '6' : 'I2C_STATE_R_MORE_TXN_PRE_ONE', - '7' : 'I2C_STATE_R_MORE_TXN_PRE_FIRST', - '8' : 'I2C_STATE_R_MORE_TXN_PRE_MIDDLE', - '9' : 'I2C_STATE_R_MORE_TXN_LAST', - '10' : 'I2C_STATE_R_MORE_TXN_POST_LAST', - '11' : 'R_LAST_TXN_ADDR', - '12' : 'I2C_STATE_R_LAST_TXN_PRE_ONE', - '13' : 'I2C_STATE_R_LAST_TXN_PRE_FIRST', - '14' : 'I2C_STATE_R_LAST_TXN_PRE_MIDDLE', - '15' : 'I2C_STATE_R_LAST_TXN_PRE_LAST', - '16' : 'I2C_STATE_R_LAST_TXN_POST_LAST', - '17' : 'I2C_STATE_W_MORE_TXN_ADDR', - '18' : 'I2C_STATE_W_MORE_TXN_MIDDLE', - '19' : 'I2C_STATE_W_MORE_TXN_LAST', - '20' : 'I2C_STATE_W_LAST_TXN_ADDR', - '21' : 'I2C_STATE_W_LAST_TXN_MIDDLE', - '22' : 'I2C_STATE_W_LAST_TXN_LAST', - '23' : 'I2C_STATE_NACK', - } - ), -] - - -class I2CStats(uavobject.UAVObject): - ## Object constants - OBJID = 122889918 - NAME = "I2CStats" - METANAME = "I2CStatsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = I2CStats() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/manualcontrolcommand.py b/ground/src/plugins/uavobjects/manualcontrolcommand.py deleted file mode 100644 index 94f9ca0c0..000000000 --- a/ground/src/plugins/uavobjects/manualcontrolcommand.py +++ /dev/null @@ -1,215 +0,0 @@ -## -############################################################################## -# -# @file manualcontrolcommand.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the ManualControlCommand object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: manualcontrolcommand.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Connected', - 'b', - 1, - [ - '0', - ], - { - '0' : 'False', - '1' : 'True', - } - ), - uavobject.UAVObjectField( - 'Armed', - 'b', - 1, - [ - '0', - ], - { - '0' : 'False', - '1' : 'True', - } - ), - uavobject.UAVObjectField( - 'Roll', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Pitch', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Yaw', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Throttle', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'FlightMode', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Manual', - '1' : 'Stabilized', - '2' : 'Auto', - } - ), - uavobject.UAVObjectField( - 'StabilizationSettings', - 'b', - 3, - [ - 'Roll', - 'Pitch', - 'Yaw', - ], - { - '0' : 'None', - '1' : 'Rate', - '2' : 'Attitude', - } - ), - uavobject.UAVObjectField( - 'Accessory1', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Accessory2', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Accessory3', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Channel', - 'h', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), -] - - -class ManualControlCommand(uavobject.UAVObject): - ## Object constants - OBJID = 2841592332 - NAME = "ManualControlCommand" - METANAME = "ManualControlCommandMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = ManualControlCommand() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/manualcontrolsettings.py b/ground/src/plugins/uavobjects/manualcontrolsettings.py deleted file mode 100644 index a20d330d5..000000000 --- a/ground/src/plugins/uavobjects/manualcontrolsettings.py +++ /dev/null @@ -1,386 +0,0 @@ -## -############################################################################## -# -# @file manualcontrolsettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the ManualControlSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: manualcontrolsettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'InputMode', - 'b', - 1, - [ - '0', - ], - { - '0' : 'PWM', - '1' : 'PPM', - '2' : 'Spektrum', - } - ), - uavobject.UAVObjectField( - 'Roll', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'Pitch', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'Yaw', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'Throttle', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'FlightMode', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'Accessory1', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'Accessory2', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'Accessory3', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Channel1', - '1' : 'Channel2', - '2' : 'Channel3', - '3' : 'Channel4', - '4' : 'Channel5', - '5' : 'Channel6', - '6' : 'Channel7', - '7' : 'Channel8', - '8' : 'None', - } - ), - uavobject.UAVObjectField( - 'Pos1StabilizationSettings', - 'b', - 3, - [ - 'Roll', - 'Pitch', - 'Yaw', - ], - { - '0' : 'None', - '1' : 'Rate', - '2' : 'Attitude', - } - ), - uavobject.UAVObjectField( - 'Pos2StabilizationSettings', - 'b', - 3, - [ - 'Roll', - 'Pitch', - 'Yaw', - ], - { - '0' : 'None', - '1' : 'Rate', - '2' : 'Attitude', - } - ), - uavobject.UAVObjectField( - 'Pos3StabilizationSettings', - 'b', - 3, - [ - 'Roll', - 'Pitch', - 'Yaw', - ], - { - '0' : 'None', - '1' : 'Rate', - '2' : 'Attitude', - } - ), - uavobject.UAVObjectField( - 'Pos1FlightMode', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Manual', - '1' : 'Stabilized', - '2' : 'Auto', - } - ), - uavobject.UAVObjectField( - 'Pos2FlightMode', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Manual', - '1' : 'Stabilized', - '2' : 'Auto', - } - ), - uavobject.UAVObjectField( - 'Pos3FlightMode', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Manual', - '1' : 'Stabilized', - '2' : 'Auto', - } - ), - uavobject.UAVObjectField( - 'ChannelMax', - 'h', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), - uavobject.UAVObjectField( - 'ChannelNeutral', - 'h', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), - uavobject.UAVObjectField( - 'ChannelMin', - 'h', - 8, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - ], - { - } - ), - uavobject.UAVObjectField( - 'ArmedTimeout', - 'H', - 1, - [ - '0', - ], - { - } - ), -] - - -class ManualControlSettings(uavobject.UAVObject): - ## Object constants - OBJID = 157988682 - NAME = "ManualControlSettings" - METANAME = "ManualControlSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = ManualControlSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/mixersettings.py b/ground/src/plugins/uavobjects/mixersettings.py deleted file mode 100644 index 38cc34121..000000000 --- a/ground/src/plugins/uavobjects/mixersettings.py +++ /dev/null @@ -1,360 +0,0 @@ -## -############################################################################## -# -# @file mixersettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the MixerSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: mixersettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'MaxAccel', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'FeedForward', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'AccelTime', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'DecelTime', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'ThrottleCurve1', - 'f', - 5, - [ - '0', - '25', - '50', - '75', - '100', - ], - { - } - ), - uavobject.UAVObjectField( - 'ThrottleCurve2', - 'f', - 5, - [ - '0', - '25', - '50', - '75', - '100', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer1Type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disabled', - '1' : 'Motor', - '2' : 'Servo', - } - ), - uavobject.UAVObjectField( - 'Mixer1Vector', - 'b', - 5, - [ - 'ThrottleCurve1', - 'ThrottleCurve2', - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer2Type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disabled', - '1' : 'Motor', - '2' : 'Servo', - } - ), - uavobject.UAVObjectField( - 'Mixer2Vector', - 'b', - 5, - [ - 'ThrottleCurve1', - 'ThrottleCurve2', - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer3Type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disabled', - '1' : 'Motor', - '2' : 'Servo', - } - ), - uavobject.UAVObjectField( - 'Mixer3Vector', - 'b', - 5, - [ - 'ThrottleCurve1', - 'ThrottleCurve2', - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer4Type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disabled', - '1' : 'Motor', - '2' : 'Servo', - } - ), - uavobject.UAVObjectField( - 'Mixer4Vector', - 'b', - 5, - [ - 'ThrottleCurve1', - 'ThrottleCurve2', - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer5Type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disabled', - '1' : 'Motor', - '2' : 'Servo', - } - ), - uavobject.UAVObjectField( - 'Mixer5Vector', - 'b', - 5, - [ - 'ThrottleCurve1', - 'ThrottleCurve2', - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer6Type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disabled', - '1' : 'Motor', - '2' : 'Servo', - } - ), - uavobject.UAVObjectField( - 'Mixer6Vector', - 'b', - 5, - [ - 'ThrottleCurve1', - 'ThrottleCurve2', - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer7Type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disabled', - '1' : 'Motor', - '2' : 'Servo', - } - ), - uavobject.UAVObjectField( - 'Mixer7Vector', - 'b', - 5, - [ - 'ThrottleCurve1', - 'ThrottleCurve2', - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer8Type', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disabled', - '1' : 'Motor', - '2' : 'Servo', - } - ), - uavobject.UAVObjectField( - 'Mixer8Vector', - 'b', - 5, - [ - 'ThrottleCurve1', - 'ThrottleCurve2', - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), -] - - -class MixerSettings(uavobject.UAVObject): - ## Object constants - OBJID = 1336817486 - NAME = "MixerSettings" - METANAME = "MixerSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = MixerSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/mixerstatus.py b/ground/src/plugins/uavobjects/mixerstatus.py deleted file mode 100644 index 9110fc56c..000000000 --- a/ground/src/plugins/uavobjects/mixerstatus.py +++ /dev/null @@ -1,156 +0,0 @@ -## -############################################################################## -# -# @file mixerstatus.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the MixerStatus object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: mixerstatus.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Mixer1', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer2', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer3', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer4', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer5', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer6', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer7', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Mixer8', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class MixerStatus(uavobject.UAVObject): - ## Object constants - OBJID = 4137893648 - NAME = "MixerStatus" - METANAME = "MixerStatusMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = MixerStatus() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/objectpersistence.py b/ground/src/plugins/uavobjects/objectpersistence.py deleted file mode 100644 index 086078844..000000000 --- a/ground/src/plugins/uavobjects/objectpersistence.py +++ /dev/null @@ -1,123 +0,0 @@ -## -############################################################################## -# -# @file objectpersistence.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the ObjectPersistence object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: objectpersistence.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Operation', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Load', - '1' : 'Save', - '2' : 'Delete', - } - ), - uavobject.UAVObjectField( - 'Selection', - 'b', - 1, - [ - '0', - ], - { - '0' : 'SingleObject', - '1' : 'AllSettings', - '2' : 'AllMetaObjects', - '3' : 'AllObjects', - } - ), - uavobject.UAVObjectField( - 'ObjectID', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'InstanceID', - 'I', - 1, - [ - '0', - ], - { - } - ), -] - - -class ObjectPersistence(uavobject.UAVObject): - ## Object constants - OBJID = 572614706 - NAME = "ObjectPersistence" - METANAME = "ObjectPersistenceMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = ObjectPersistence() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/pipxtrememodemsettings.py b/ground/src/plugins/uavobjects/pipxtrememodemsettings.py deleted file mode 100644 index 4f5ea7f52..000000000 --- a/ground/src/plugins/uavobjects/pipxtrememodemsettings.py +++ /dev/null @@ -1,246 +0,0 @@ -## -############################################################################## -# -# @file pipxtrememodemsettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the PipXtremeModemSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: pipxtrememodemsettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Mode', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Normal', - '1' : 'Test_Carrier', - '2' : 'Test_Spectrum', - } - ), - uavobject.UAVObjectField( - 'Serial_Baudrate', - 'b', - 1, - [ - '0', - ], - { - '0' : '1200', - '1' : '2400', - '2' : '4800', - '3' : '9600', - '4' : '19200', - '5' : '38400', - '6' : '57600', - '7' : '115200', - '8' : '230400', - } - ), - uavobject.UAVObjectField( - 'Frequency_Calibration', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Frequency_Min', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Frequency_Max', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Frequency', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Max_RF_Bandwidth', - 'b', - 1, - [ - '0', - ], - { - '0' : '500', - '1' : '1000', - '2' : '2000', - '3' : '4000', - '4' : '8000', - '5' : '9600', - '6' : '16000', - '7' : '19200', - '8' : '24000', - '9' : '32000', - '10' : '64000', - '11' : '128000', - '12' : '192000', - } - ), - uavobject.UAVObjectField( - 'Max_Tx_Power', - 'b', - 1, - [ - '0', - ], - { - '0' : '1', - '1' : '2', - '2' : '5', - '3' : '8', - '4' : '11', - '5' : '14', - '6' : '17', - '7' : '20', - } - ), - uavobject.UAVObjectField( - 'Tx_Data_Wait', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'AES_Encryption', - 'b', - 1, - [ - '0', - ], - { - '0' : 'False', - '1' : 'True', - } - ), - uavobject.UAVObjectField( - 'AES_EncryptionKey', - 'B', - 16, - [ - '0', - '1', - '2', - '3', - '4', - '5', - '6', - '7', - '8', - '9', - '10', - '11', - '12', - '13', - '14', - '15', - ], - { - } - ), - uavobject.UAVObjectField( - 'Paired_Serial_Number', - 'I', - 1, - [ - '0', - ], - { - } - ), -] - - -class PipXtremeModemSettings(uavobject.UAVObject): - ## Object constants - OBJID = 444830632 - NAME = "PipXtremeModemSettings" - METANAME = "PipXtremeModemSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = PipXtremeModemSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/pipxtrememodemstatus.py b/ground/src/plugins/uavobjects/pipxtrememodemstatus.py deleted file mode 100644 index 0e2d41ba3..000000000 --- a/ground/src/plugins/uavobjects/pipxtrememodemstatus.py +++ /dev/null @@ -1,190 +0,0 @@ -## -############################################################################## -# -# @file pipxtrememodemstatus.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the PipXtremeModemStatus object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: pipxtrememodemstatus.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Firmware_Version_Major', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Firmware_Version_Minor', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Serial_Number', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Up_Time', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Frequency', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'RF_Bandwidth', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Tx_Power', - 'b', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'State', - 'b', - 1, - [ - '0', - ], - { - '0' : 'Disconnected', - '1' : 'Connecting', - '2' : 'Connected', - '3' : 'NotReady', - } - ), - uavobject.UAVObjectField( - 'Tx_Retry', - 'H', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Tx_Data_Rate', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Rx_Data_Rate', - 'I', - 1, - [ - '0', - ], - { - } - ), -] - - -class PipXtremeModemStatus(uavobject.UAVObject): - ## Object constants - OBJID = 2490854928 - NAME = "PipXtremeModemStatus" - METANAME = "PipXtremeModemStatusMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = PipXtremeModemStatus() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/positionactual.py b/ground/src/plugins/uavobjects/positionactual.py deleted file mode 100644 index c8e1fadfa..000000000 --- a/ground/src/plugins/uavobjects/positionactual.py +++ /dev/null @@ -1,106 +0,0 @@ -## -############################################################################## -# -# @file positionactual.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the PositionActual object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: positionactual.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'North', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'East', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Down', - 'i', - 1, - [ - '0', - ], - { - } - ), -] - - -class PositionActual(uavobject.UAVObject): - ## Object constants - OBJID = 3765671478 - NAME = "PositionActual" - METANAME = "PositionActualMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = PositionActual() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/positiondesired.py b/ground/src/plugins/uavobjects/positiondesired.py deleted file mode 100644 index ba98cdf53..000000000 --- a/ground/src/plugins/uavobjects/positiondesired.py +++ /dev/null @@ -1,106 +0,0 @@ -## -############################################################################## -# -# @file positiondesired.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the PositionDesired object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: positiondesired.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'North', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'East', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Down', - 'i', - 1, - [ - '0', - ], - { - } - ), -] - - -class PositionDesired(uavobject.UAVObject): - ## Object constants - OBJID = 801433018 - NAME = "PositionDesired" - METANAME = "PositionDesiredMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = PositionDesired() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/ratedesired.py b/ground/src/plugins/uavobjects/ratedesired.py deleted file mode 100644 index 9a4110d66..000000000 --- a/ground/src/plugins/uavobjects/ratedesired.py +++ /dev/null @@ -1,106 +0,0 @@ -## -############################################################################## -# -# @file ratedesired.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the RateDesired object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: ratedesired.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Roll', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Pitch', - 'f', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Yaw', - 'f', - 1, - [ - '0', - ], - { - } - ), -] - - -class RateDesired(uavobject.UAVObject): - ## Object constants - OBJID = 3124868380 - NAME = "RateDesired" - METANAME = "RateDesiredMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = RateDesired() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/stabilizationsettings.py b/ground/src/plugins/uavobjects/stabilizationsettings.py deleted file mode 100644 index 52634dc85..000000000 --- a/ground/src/plugins/uavobjects/stabilizationsettings.py +++ /dev/null @@ -1,202 +0,0 @@ -## -############################################################################## -# -# @file stabilizationsettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the StabilizationSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: stabilizationsettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'RollMax', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'PitchMax', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'YawMax', - 'B', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'ManualRate', - 'f', - 3, - [ - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'MaximumRate', - 'f', - 3, - [ - 'Roll', - 'Pitch', - 'Yaw', - ], - { - } - ), - uavobject.UAVObjectField( - 'RollRatePI', - 'f', - 3, - [ - 'Kp', - 'Ki', - 'ILimit', - ], - { - } - ), - uavobject.UAVObjectField( - 'PitchRatePI', - 'f', - 3, - [ - 'Kp', - 'Ki', - 'ILimit', - ], - { - } - ), - uavobject.UAVObjectField( - 'YawRatePI', - 'f', - 3, - [ - 'Kp', - 'Ki', - 'ILimit', - ], - { - } - ), - uavobject.UAVObjectField( - 'RollPI', - 'f', - 3, - [ - 'Kp', - 'Ki', - 'ILimit', - ], - { - } - ), - uavobject.UAVObjectField( - 'PitchPI', - 'f', - 3, - [ - 'Kp', - 'Ki', - 'ILimit', - ], - { - } - ), - uavobject.UAVObjectField( - 'YawPI', - 'f', - 3, - [ - 'Kp', - 'Ki', - 'ILimit', - ], - { - } - ), -] - - -class StabilizationSettings(uavobject.UAVObject): - ## Object constants - OBJID = 3792991236 - NAME = "StabilizationSettings" - METANAME = "StabilizationSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = StabilizationSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/systemalarms.py b/ground/src/plugins/uavobjects/systemalarms.py deleted file mode 100644 index 6497ee550..000000000 --- a/ground/src/plugins/uavobjects/systemalarms.py +++ /dev/null @@ -1,104 +0,0 @@ -## -############################################################################## -# -# @file systemalarms.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the SystemAlarms object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: systemalarms.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Alarm', - 'b', - 14, - [ - 'OutOfMemory', - 'StackOverflow', - 'CPUOverload', - 'EventSystem', - 'SDCard', - 'Telemetry', - 'ManualControl', - 'Actuator', - 'Stabilization', - 'AHRSComms', - 'Battery', - 'FlightTime', - 'I2C', - 'GPS', - ], - { - '0' : 'OK', - '1' : 'Warning', - '2' : 'Error', - '3' : 'Critical', - '4' : 'Uninitialised', - } - ), -] - - -class SystemAlarms(uavobject.UAVObject): - ## Object constants - OBJID = 2311314672 - NAME = "SystemAlarms" - METANAME = "SystemAlarmsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = SystemAlarms() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/systemsettings.py b/ground/src/plugins/uavobjects/systemsettings.py deleted file mode 100644 index 7d42c1c53..000000000 --- a/ground/src/plugins/uavobjects/systemsettings.py +++ /dev/null @@ -1,102 +0,0 @@ -## -############################################################################## -# -# @file systemsettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the SystemSettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: systemsettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'AirframeType', - 'b', - 1, - [ - '0', - ], - { - '0' : 'FixedWing', - '1' : 'FixedWingElevon', - '2' : 'FixedWingVtail', - '3' : 'VTOL', - '4' : 'HeliCP', - '5' : 'QuadX', - '6' : 'QuadP', - '7' : 'Hexa', - '8' : 'Octo', - '9' : 'Custom', - '10' : 'HexaX', - '11' : 'OctoV', - '12' : 'OctoCoaxP', - '13' : 'OctoCoaxX', - '14' : 'HexaCoax', - '15' : 'Tri', - } - ), -] - - -class SystemSettings(uavobject.UAVObject): - ## Object constants - OBJID = 59202798 - NAME = "SystemSettings" - METANAME = "SystemSettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = SystemSettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/systemstats.py b/ground/src/plugins/uavobjects/systemstats.py deleted file mode 100644 index c5d84cf50..000000000 --- a/ground/src/plugins/uavobjects/systemstats.py +++ /dev/null @@ -1,106 +0,0 @@ -## -############################################################################## -# -# @file systemstats.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the SystemStats object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: systemstats.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'FlightTime', - 'I', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'HeapRemaining', - 'H', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'CPULoad', - 'B', - 1, - [ - '0', - ], - { - } - ), -] - - -class SystemStats(uavobject.UAVObject): - ## Object constants - OBJID = 680908530 - NAME = "SystemStats" - METANAME = "SystemStatsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = SystemStats() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/taskinfo.py b/ground/src/plugins/uavobjects/taskinfo.py deleted file mode 100644 index 52a76c5bc..000000000 --- a/ground/src/plugins/uavobjects/taskinfo.py +++ /dev/null @@ -1,122 +0,0 @@ -## -############################################################################## -# -# @file taskinfo.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the TaskInfo object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: taskinfo.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'StackRemaining', - 'H', - 13, - [ - 'System', - 'Actuator', - 'TelemetryTx', - 'TelemetryTxPri', - 'TelemetryRx', - 'GPS', - 'ManualControl', - 'Altitude', - 'AHRSComms', - 'Stabilization', - 'Guidance', - 'Watchdog', - 'FlightPlan', - ], - { - } - ), - uavobject.UAVObjectField( - 'Running', - 'b', - 13, - [ - 'System', - 'Actuator', - 'TelemetryTx', - 'TelemetryTxPri', - 'TelemetryRx', - 'GPS', - 'ManualControl', - 'Altitude', - 'AHRSComms', - 'Stabilization', - 'Guidance', - 'Watchdog', - 'FlightPlan', - ], - { - '0' : 'False', - '1' : 'True', - } - ), -] - - -class TaskInfo(uavobject.UAVObject): - ## Object constants - OBJID = 1358273008 - NAME = "TaskInfo" - METANAME = "TaskInfoMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = TaskInfo() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/telemetrysettings.py b/ground/src/plugins/uavobjects/telemetrysettings.py deleted file mode 100644 index e19fda943..000000000 --- a/ground/src/plugins/uavobjects/telemetrysettings.py +++ /dev/null @@ -1,93 +0,0 @@ -## -############################################################################## -# -# @file telemetrysettings.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the TelemetrySettings object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: telemetrysettings.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'Speed', - 'b', - 1, - [ - '0', - ], - { - '0' : '2400', - '1' : '4800', - '2' : '9600', - '3' : '19200', - '4' : '38400', - '5' : '57600', - '6' : '115200', - } - ), -] - - -class TelemetrySettings(uavobject.UAVObject): - ## Object constants - OBJID = 2785592614 - NAME = "TelemetrySettings" - METANAME = "TelemetrySettingsMeta" - ISSINGLEINST = 1 - ISSETTINGS = 1 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = TelemetrySettings() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/velocityactual.py b/ground/src/plugins/uavobjects/velocityactual.py deleted file mode 100644 index 6dd455eae..000000000 --- a/ground/src/plugins/uavobjects/velocityactual.py +++ /dev/null @@ -1,106 +0,0 @@ -## -############################################################################## -# -# @file velocityactual.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the VelocityActual object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: velocityactual.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'North', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'East', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Down', - 'i', - 1, - [ - '0', - ], - { - } - ), -] - - -class VelocityActual(uavobject.UAVObject): - ## Object constants - OBJID = 1207999624 - NAME = "VelocityActual" - METANAME = "VelocityActualMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = VelocityActual() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/velocitydesired.py b/ground/src/plugins/uavobjects/velocitydesired.py deleted file mode 100644 index c9f33268f..000000000 --- a/ground/src/plugins/uavobjects/velocitydesired.py +++ /dev/null @@ -1,106 +0,0 @@ -## -############################################################################## -# -# @file velocitydesired.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the VelocityDesired object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: velocitydesired.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'North', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'East', - 'i', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'Down', - 'i', - 1, - [ - '0', - ], - { - } - ), -] - - -class VelocityDesired(uavobject.UAVObject): - ## Object constants - OBJID = 305094202 - NAME = "VelocityDesired" - METANAME = "VelocityDesiredMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = VelocityDesired() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main() diff --git a/ground/src/plugins/uavobjects/watchdogstatus.py b/ground/src/plugins/uavobjects/watchdogstatus.py deleted file mode 100644 index 04742c62a..000000000 --- a/ground/src/plugins/uavobjects/watchdogstatus.py +++ /dev/null @@ -1,96 +0,0 @@ -## -############################################################################## -# -# @file watchdogstatus.py -# @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -# @brief Implementation of the WatchdogStatus object. This file has been -# automatically generated by the UAVObjectGenerator. -# -# @note Object definition file: watchdogstatus.xml. -# This is an automatically generated file. -# DO NOT modify manually. -# -# @see The GNU Public License (GPL) Version 3 -# -#############################################################################/ -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - - -import uavobject - -import struct -from collections import namedtuple - -# This is a list of instances of the data fields contained in this object -_fields = [ \ - uavobject.UAVObjectField( - 'BootupFlags', - 'H', - 1, - [ - '0', - ], - { - } - ), - uavobject.UAVObjectField( - 'ActiveFlags', - 'H', - 1, - [ - '0', - ], - { - } - ), -] - - -class WatchdogStatus(uavobject.UAVObject): - ## Object constants - OBJID = 3594971408 - NAME = "WatchdogStatus" - METANAME = "WatchdogStatusMeta" - ISSINGLEINST = 1 - ISSETTINGS = 0 - - def __init__(self): - uavobject.UAVObject.__init__(self, - self.OBJID, - self.NAME, - self.METANAME, - 0, - self.ISSINGLEINST) - - for f in _fields: - self.add_field(f) - - def __str__(self): - s = ("0x%08X (%10u) %-30s %3u bytes format '%s'\n" - % (self.OBJID, self.OBJID, self.NAME, self.get_struct().size, self.get_struct().format)) - for f in self.get_tuple()._fields: - s += ("\t%s\n" % f) - return (s) - -def main(): - # Instantiate the object and dump out some interesting info - x = WatchdogStatus() - print (x) - -if __name__ == "__main__": - #import pdb ; pdb.run('main()') - main()