aboutsummaryrefslogtreecommitdiff
path: root/mavlink-library/src/main/twirl/org/mavlink/messages/messages.scala.txt
blob: 731464d771f9a2f5f1e5f5c06e4574fd9d71663f (plain) (blame)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
@(__context: Context, __messages: Set[Message])@org.mavlink.txt._header(__context)
package org.mavlink.messages

import java.nio.ByteBuffer
import java.nio.ByteOrder
import java.nio.charset.Charset

@__scalaMessageType(message: Message) = {@StringUtils.Camelify(message.name)}

@__scalaFieldName(field: Field) = {@StringUtils.camelify(field.name)}

@__scalaFieldType(tpe: Type) = {@tpe match {
  case IntType(1, _) => {Byte}
  case IntType(2, _) => {Short}
  case IntType(4, _) => {Int}
  case IntType(8, _) => {Long}
  case FloatType(4) => {Float}
  case FloatType(8) => {Double}
  case StringType(_) => {String}
  case CharType => {Byte}
  case ArrayType(underlying, _) => {Seq[@__scalaFieldType(underlying)]}
  case t => {sys.error("unsupported type: " + @t)}
}}
@__scalaFieldFormal(field: Field) = {@__scalaFieldName(field): @__scalaFieldType(field.tpe)}

@__bufferReadMethod(buffer: String, tpe: Type) = {@tpe match {
  case IntType(1, _) => {@{buffer}.get()}
  case IntType(2, _) => {@{buffer}.getShort()}
  case IntType(4, _) => {@{buffer}.getInt()}
  case IntType(8, _) => {@{buffer}.getLong()}
  case FloatType(4) => {@{buffer}.getFloat()}
  case FloatType(8) => {@{buffer}.getDouble()}
  case StringType(maxLength) =>{{
    val bytes = new Array[Byte](@maxLength)
    @{buffer}.get(bytes, 0, @maxLength)
    val length = bytes.indexOf(0) match {
      case -1 => @maxLength
      case i => i
    }
    new String(bytes, 0, length, Charset.forName("UTF-8"))
  }}
  case CharType => {@{buffer}.get()}
  case ArrayType(underlying, length) => {for (i <- 0 until @length) yield {@__bufferReadMethod(buffer, underlying)}}
  case t => {sys.error("unsupported type: " + @t)}
}}
@__bufferWriteMethod(buffer: String, data: String, tpe: Type) = {@tpe match {
  case IntType(1, _) => {@{buffer}.put(@data)}
  case IntType(2, _) => {@{buffer}.putShort(@data)}
  case IntType(4, _) => {@{buffer}.putInt(@data)}
  case IntType(8, _) => {@{buffer}.putLong(@data)}
  case FloatType(4) => {@{buffer}.putFloat(@data)}
  case FloatType(8) => {@{buffer}.putDouble(@data)}
  case StringType(maxLength) => {
  {
    val bytes = @{data}.getBytes(Charset.forName("UTF-8"))
    val endPosition = @{buffer}.position + @maxLength
    @{buffer}.put(bytes, 0, math.min(bytes.length, @maxLength))
    while (@{buffer}.position < endPosition) {
      @{buffer}.put(0: Byte)
    }
  }}
  case CharType => {@{buffer}.put(@data)}
  case ArrayType(underlying, length) => {for (i <- 0 until @length) {@__bufferWriteMethod(buffer, data + "(i)", underlying)}}
  case t => {sys.error("unsupported type: " + @t)}
}}

@__commentParagraphs(paragraphs:  Seq[String]) = {@paragraphs.mkString("/**\n * ", "\n * ", "\n */")}
@__comment(message: Message) = {@__commentParagraphs(message.description.grouped(100).toList ++ message.fields.map(field => "@param " + __scalaFieldName(field) + " " + field.description))}

/** Marker trait for MAVLink messages. All supported messages extend this trait. */
sealed trait Message

@for(__msg <- __messages) {
@__comment(__msg)
case class @{__scalaMessageType(__msg)}(@__msg.fields.map(__scalaFieldFormal).mkString(", ")) extends Message
}

/**
 * Wraps an unknown message.
 * @@param id the ID of the message
 * @@param payload the message's contents
 */
case class Unknown(id: Byte, payload: Array[Byte]) extends Message

/**
 * Provides utility methods for converting data to and from MAVLink messages.
 */
object Message {

  /**
   * Interprets an ID and payload as a message. The contents must be ordered
   * according to the MAVLink specification.
   * @@param id ID of the message
   * @@param payload contents of the message
   * @@return payload interpreted as a message or 'Unknown' in case of an unknown ID
   */
  def unpack(id: Byte, payload: Array[Byte]): Message = {
    val buffer = ByteBuffer.wrap(payload)
    buffer.order(ByteOrder.LITTLE_ENDIAN)
    id match {
    @for(__msg <- __messages) {
      case @__msg.id =>
        @for(__field <- __msg.orderedFields) {val @__scalaFieldFormal(__field) = @__bufferReadMethod("buffer", __field.tpe)
        }
        @{__scalaMessageType(__msg)}(@__msg.fields.map(__scalaFieldName(_)).mkString(", "))
    }
      case u => Unknown(u, payload)
    }
  }

  /**
   * Encodes a message according to the MAVLink specification.
   * @@param message the message to write
   * @@return (id, payload) id and payload of the encoded message
   */
  def pack(message: Message): (Byte, Array[Byte]) = message match {
    @for(__msg <- __messages) {
      case m: @__scalaMessageType(__msg) =>
        val arr = new Array[Byte](@__msg.length)
        val buffer = ByteBuffer.wrap(arr)
	buffer.order(ByteOrder.LITTLE_ENDIAN)

        @for(__field <- __msg.orderedFields) {@__bufferWriteMethod("buffer", "m." + __scalaFieldName(__field), __field.tpe)
        }
        (@__msg.id, arr)
    }
    case u: Unknown =>
      (u.id, u.payload)
  }
}