GimbalDeviceAttitudeStatus.parse constructor

GimbalDeviceAttitudeStatus.parse(
  1. ByteData data_
)

Implementation

factory GimbalDeviceAttitudeStatus.parse(ByteData data_) {
  if (data_.lengthInBytes < GimbalDeviceAttitudeStatus.mavlinkEncodedLength) {
    var len =
        GimbalDeviceAttitudeStatus.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 q = MavlinkMessage.asFloat32List(data_, 4, 4);
  var angularVelocityX = data_.getFloat32(20, Endian.little);
  var angularVelocityY = data_.getFloat32(24, Endian.little);
  var angularVelocityZ = data_.getFloat32(28, Endian.little);
  var failureFlags = data_.getUint32(32, Endian.little);
  var flags = data_.getUint16(36, Endian.little);
  var targetSystem = data_.getUint8(38);
  var targetComponent = data_.getUint8(39);
  var deltaYaw = data_.getFloat32(40, Endian.little);
  var deltaYawVelocity = data_.getFloat32(44, Endian.little);
  var gimbalDeviceId = data_.getUint8(48);

  return GimbalDeviceAttitudeStatus(
      timeBootMs: timeBootMs,
      q: q,
      angularVelocityX: angularVelocityX,
      angularVelocityY: angularVelocityY,
      angularVelocityZ: angularVelocityZ,
      failureFlags: failureFlags,
      flags: flags,
      targetSystem: targetSystem,
      targetComponent: targetComponent,
      deltaYaw: deltaYaw,
      deltaYawVelocity: deltaYawVelocity,
      gimbalDeviceId: gimbalDeviceId);
}