GimbalDeviceInformation.parse constructor

GimbalDeviceInformation.parse(
  1. ByteData data_
)

Implementation

factory GimbalDeviceInformation.parse(ByteData data_) {
  if (data_.lengthInBytes < GimbalDeviceInformation.mavlinkEncodedLength) {
    var len =
        GimbalDeviceInformation.mavlinkEncodedLength - data_.lengthInBytes;
    var d = data_.buffer.asUint8List() + List<int>.filled(len, 0);
    data_ = Uint8List.fromList(d).buffer.asByteData();
  }
  var uid = data_.getUint64(0, Endian.little);
  var timeBootMs = data_.getUint32(8, Endian.little);
  var firmwareVersion = data_.getUint32(12, Endian.little);
  var hardwareVersion = data_.getUint32(16, Endian.little);
  var rollMin = data_.getFloat32(20, Endian.little);
  var rollMax = data_.getFloat32(24, Endian.little);
  var pitchMin = data_.getFloat32(28, Endian.little);
  var pitchMax = data_.getFloat32(32, Endian.little);
  var yawMin = data_.getFloat32(36, Endian.little);
  var yawMax = data_.getFloat32(40, Endian.little);
  var capFlags = data_.getUint16(44, Endian.little);
  var customCapFlags = data_.getUint16(46, Endian.little);
  var vendorName = MavlinkMessage.asInt8List(data_, 48, 32);
  var modelName = MavlinkMessage.asInt8List(data_, 80, 32);
  var customName = MavlinkMessage.asInt8List(data_, 112, 32);
  var gimbalDeviceId = data_.getUint8(144);

  return GimbalDeviceInformation(
      uid: uid,
      timeBootMs: timeBootMs,
      firmwareVersion: firmwareVersion,
      hardwareVersion: hardwareVersion,
      rollMin: rollMin,
      rollMax: rollMax,
      pitchMin: pitchMin,
      pitchMax: pitchMax,
      yawMin: yawMin,
      yawMax: yawMax,
      capFlags: capFlags,
      customCapFlags: customCapFlags,
      vendorName: vendorName,
      modelName: modelName,
      customName: customName,
      gimbalDeviceId: gimbalDeviceId);
}