blob: b52174687a6cf131cd004186835f49e846c490fb (
plain) (
tree)
|
|
@(__context: Context, __maxPayloadLength: Int, __extraCrcs: Seq[Byte])@_header(__context)
package org.mavlink
import scala.collection.mutable.ArrayBuilder
/**
* Represents a MAVLink packet.
* Note that due to performance reasons, the packet's payload contents are mutable.
* @@param seq sequence number
* @@param systemId system ID of sender
* @@param componentId component ID of sender
* @@param messageId MAVLink message identification (this depends on the dialect used)
* @@param payload message contents
*/
case class Packet(
seq: Byte,
systemId: Byte,
componentId: Byte,
messageId: Byte,
payload: Array[Byte]
) {
lazy val crc = {
var c = new Crc()
c = c.accumulate(payload.length.toByte)
c = c.accumulate(seq)
c = c.accumulate(systemId)
c = c.accumulate(componentId)
c = c.accumulate(messageId)
for (b <- payload) c = c.accumulate(b)
c = c.accumulate(Packet.extraCrc(messageId))
c
}
val toArray = {
val builder = ArrayBuilder.make[Byte]
builder += Packet.Stx
builder += payload.length.toByte
builder += seq
builder += systemId
builder += componentId
builder += messageId
builder ++= payload
builder += crc.lsb
builder += crc.msb
builder.result
}
}
object Packet {
/** Start byte signaling the beginning of a packet. */
final val Stx: Byte = (0xfe).toByte
/** Maximum length of a payload contained in a packet. */
final val MaxPayloadLength: Int = @__maxPayloadLength
/** Additional CRCs indexed by message ID (see MAVLink specification). */
final val ExtraCrcs: Seq[Byte] = Array[Byte](
@__extraCrcs.map(_ formatted "%3d").grouped(10).map(_.mkString(",")).mkString(",\n ")
)
/** Utility function to index ExtraCrcs with a byte. */
def extraCrc(id: Byte) = ExtraCrcs(id & 0xff)
/** An invalid packet with no payload. */
def empty = Packet(0, 0, 0, -128, Array(0: Byte))
}
|