MavDataDecoder

interface MavDataDecoder

Reads primitives from a ByteArray according to the little-endian byte order.

Properties

Link copied to clipboard
abstract val remaining: Int

The number of bytes remaining in the array.

Functions

Link copied to clipboard
abstract fun decodeByte(): Byte

Reads a Byte from the array's current position, and then increments the position.

Link copied to clipboard
abstract fun decodeByteArray(dst: ByteArray, offset: Int = 0, length: Int = dst.size)

Reads length number of bytes from the array's current position into dst with the given offset, and then increments the position.

Link copied to clipboard
abstract fun decodeInt(): Int

Reads a Int from the array's current position, and then increments the position.

Link copied to clipboard
abstract fun decodeLong(): Long

Reads a Long from the array's current position, and then increments the position.

Link copied to clipboard
abstract fun decodeShort(): Short

Reads a Short from the array's current position, and then increments the position.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a UInt representing the MAVLink bitmask value. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a Char from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a Double/Float64 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded Double/Float64 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a UInt representing the MAVLink enum value. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a Float/Float32 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded Float/Float32 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a Short/Int16 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded Short/Int16 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a Int/Int32 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded Int/Int32 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a Long/Int64 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded Long/Int64 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a Byte/Int8 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded Byte/Int8 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns the signed value encoded as Long. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a String of the given length from the array's current position using the UTF-8 encoding, and then increments the position. If there are not enough bytes in the array, the remaining length is ignored.

Link copied to clipboard

Reads a UShort/UInt16 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded UShort/UInt16 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a UInt/UInt32 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded UInt/UInt32 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a ULong/UInt64 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded ULong/UInt64 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads a UByte/UInt8 from the array's current position, and then increments the position. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns a List of the decoded UByte/UInt8 values. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.

Link copied to clipboard

Reads dataSize number of bytes from the array's current position, and then increments the position. Returns the unsigned value encoded as a Long. If there are not enough bytes in the array, it assumes that the remaining length is padded with zeroes.