SysStatus.parse constructor
SysStatus.parse(
- ByteData data_
Implementation
factory SysStatus.parse(ByteData data_) {
if (data_.lengthInBytes < SysStatus.mavlinkEncodedLength) {
var len = SysStatus.mavlinkEncodedLength - data_.lengthInBytes;
var d = data_.buffer.asUint8List() + List<int>.filled(len, 0);
data_ = Uint8List.fromList(d).buffer.asByteData();
}
var onboardControlSensorsPresent = data_.getUint32(0, Endian.little);
var onboardControlSensorsEnabled = data_.getUint32(4, Endian.little);
var onboardControlSensorsHealth = data_.getUint32(8, Endian.little);
var load = data_.getUint16(12, Endian.little);
var voltageBattery = data_.getUint16(14, Endian.little);
var currentBattery = data_.getInt16(16, Endian.little);
var dropRateComm = data_.getUint16(18, Endian.little);
var errorsComm = data_.getUint16(20, Endian.little);
var errorsCount1 = data_.getUint16(22, Endian.little);
var errorsCount2 = data_.getUint16(24, Endian.little);
var errorsCount3 = data_.getUint16(26, Endian.little);
var errorsCount4 = data_.getUint16(28, Endian.little);
var batteryRemaining = data_.getInt8(30);
var onboardControlSensorsPresentExtended =
data_.getUint32(31, Endian.little);
var onboardControlSensorsEnabledExtended =
data_.getUint32(35, Endian.little);
var onboardControlSensorsHealthExtended =
data_.getUint32(39, Endian.little);
return SysStatus(
onboardControlSensorsPresent: onboardControlSensorsPresent,
onboardControlSensorsEnabled: onboardControlSensorsEnabled,
onboardControlSensorsHealth: onboardControlSensorsHealth,
load: load,
voltageBattery: voltageBattery,
currentBattery: currentBattery,
dropRateComm: dropRateComm,
errorsComm: errorsComm,
errorsCount1: errorsCount1,
errorsCount2: errorsCount2,
errorsCount3: errorsCount3,
errorsCount4: errorsCount4,
batteryRemaining: batteryRemaining,
onboardControlSensorsPresentExtended:
onboardControlSensorsPresentExtended,
onboardControlSensorsEnabledExtended:
onboardControlSensorsEnabledExtended,
onboardControlSensorsHealthExtended:
onboardControlSensorsHealthExtended);
}