diff options
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.txt | 4 |
1 files changed, 2 insertions, 2 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 e973547..939c1d1 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 @@ -28,7 +28,7 @@ import java.nio.charset.Charset case FloatType(4) => {@{buffer}.getFloat()} case FloatType(8) => {@{buffer}.getDouble()} case StringType(maxLength) =>{{ - val bytes = Array[Byte](@maxLength) + val bytes = new Array[Byte](@maxLength) @{buffer}.get(bytes, 0, @maxLength) val length = bytes.indexOf(0) match { case -1 => @maxLength @@ -49,7 +49,7 @@ import java.nio.charset.Charset { val bytes = @{data}.getBytes(Charset.forName("UTF-8")) val endPosition = @{buffer}.position + @maxLength - @{buffer}.put(bytes, 0, math.max(bytes.length, @maxLength)) + @{buffer}.put(bytes, 0, math.min(bytes.length, @maxLength)) while (@{buffer}.position < endPosition) { @{buffer}.put(0: Byte) } |