GimbalManagerInformation.parse constructor
GimbalManagerInformation.parse(
- ByteData data_
Implementation
factory GimbalManagerInformation.parse(ByteData data_) {
if (data_.lengthInBytes < GimbalManagerInformation.mavlinkEncodedLength) {
var len =
GimbalManagerInformation.mavlinkEncodedLength - data_.lengthInBytes;
var d = data_.buffer.asUint8List() + List<int>.filled(len, 0);
data_ = Uint8List.fromList(d).buffer.asByteData();
}
var timeBootMs = data_.getUint32(0, Endian.little);
var capFlags = data_.getUint32(4, Endian.little);
var rollMin = data_.getFloat32(8, Endian.little);
var rollMax = data_.getFloat32(12, Endian.little);
var pitchMin = data_.getFloat32(16, Endian.little);
var pitchMax = data_.getFloat32(20, Endian.little);
var yawMin = data_.getFloat32(24, Endian.little);
var yawMax = data_.getFloat32(28, Endian.little);
var gimbalDeviceId = data_.getUint8(32);
return GimbalManagerInformation(
timeBootMs: timeBootMs,
capFlags: capFlags,
rollMin: rollMin,
rollMax: rollMax,
pitchMin: pitchMin,
pitchMax: pitchMax,
yawMin: yawMin,
yawMax: yawMax,
gimbalDeviceId: gimbalDeviceId);
}