aboutsummaryrefslogtreecommitdiff
path: root/mavlink-library/src/main/twirl/org/mavlink/messages/messages.scala.txt
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink-library/src/main/twirl/org/mavlink/messages/messages.scala.txt')
-rw-r--r--mavlink-library/src/main/twirl/org/mavlink/messages/messages.scala.txt5
1 files changed, 4 insertions, 1 deletions
diff --git a/mavlink-library/src/main/twirl/org/mavlink/messages/messages.scala.txt b/mavlink-library/src/main/twirl/org/mavlink/messages/messages.scala.txt
index 7a60c0a..7290d4c 100644
--- a/mavlink-library/src/main/twirl/org/mavlink/messages/messages.scala.txt
+++ b/mavlink-library/src/main/twirl/org/mavlink/messages/messages.scala.txt
@@ -2,6 +2,7 @@
package org.mavlink.messages
import java.nio.ByteBuffer
+import java.nio.ByteOrder
import java.nio.charset.Charset
@__scalaMessageType(message: Message) = {@StringUtils.Camelify(message.name)}
@@ -89,6 +90,7 @@ object Message {
*/
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 =>
@@ -110,6 +112,7 @@ object Message {
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)
}
@@ -118,4 +121,4 @@ object Message {
case u: Unknown =>
(u.id, u.payload)
}
-} \ No newline at end of file
+}