123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202 |
- /* AUTO-GENERATED FILE. DO NOT MODIFY.
- *
- * This class was automatically generated by the
- * java mavlink generator tool. It should not be modified by hand.
- */
- package com.MAVLink.Messages;
- import java.nio.ByteBuffer;
- public class MAVLinkPayload {
- private static final byte UNSIGNED_BYTE_MIN_VALUE = 0;
- private static final short UNSIGNED_BYTE_MAX_VALUE = Byte.MAX_VALUE - Byte.MIN_VALUE;
- private static final short UNSIGNED_SHORT_MIN_VALUE = 0;
- private static final int UNSIGNED_SHORT_MAX_VALUE = Short.MAX_VALUE - Short.MIN_VALUE;
- private static final int UNSIGNED_INT_MIN_VALUE = 0;
- private static final long UNSIGNED_INT_MAX_VALUE = (long) Integer.MAX_VALUE - Integer.MIN_VALUE;
- private static final long UNSIGNED_LONG_MIN_VALUE = 0;
- public static final int MAX_PAYLOAD_SIZE = 255;
-
- public final ByteBuffer payload;
- public int index;
- public MAVLinkPayload(int payloadSize) {
- if(payloadSize > MAX_PAYLOAD_SIZE) {
- payload = ByteBuffer.allocate(MAX_PAYLOAD_SIZE);
- } else {
- payload = ByteBuffer.allocate(payloadSize);
- }
- }
- public ByteBuffer getData() {
- return payload;
- }
- public int size() {
- return payload.position();
- }
- public void add(byte c) {
- payload.put(c);
- }
- public void resetIndex() {
- index = 0;
- }
- public byte getByte() {
- byte result = 0;
- result |= (payload.get(index + 0) & 0xFF);
- index += 1;
- return result;
- }
- public short getUnsignedByte(){
- short result = 0;
- result |= payload.get(index + 0) & 0xFF;
- index+= 1;
- return result;
- }
- public short getShort() {
- short result = 0;
- result |= (payload.get(index + 1) & 0xFF) << 8;
- result |= (payload.get(index + 0) & 0xFF);
- index += 2;
- return result;
- }
- public int getUnsignedShort(){
- int result = 0;
- result |= (payload.get(index + 1) & 0xFF) << 8;
- result |= (payload.get(index + 0) & 0xFF);
- index += 2;
- return result;
- }
- public int getInt() {
- int result = 0;
- result |= (payload.get(index + 3) & 0xFF) << 24;
- result |= (payload.get(index + 2) & 0xFF) << 16;
- result |= (payload.get(index + 1) & 0xFF) << 8;
- result |= (payload.get(index + 0) & 0xFF);
- index += 4;
- return result;
- }
- public long getUnsignedInt(){
- long result = 0;
- result |= (payload.get(index + 3) & 0xFFL) << 24;
- result |= (payload.get(index + 2) & 0xFFL) << 16;
- result |= (payload.get(index + 1) & 0xFFL) << 8;
- result |= (payload.get(index + 0) & 0xFFL);
- index += 4;
- return result;
- }
- public long getLong() {
- long result = 0;
- result |= (payload.get(index + 7) & 0xFFL) << 56;
- result |= (payload.get(index + 6) & 0xFFL) << 48;
- result |= (payload.get(index + 5) & 0xFFL) << 40;
- result |= (payload.get(index + 4) & 0xFFL) << 32;
- result |= (payload.get(index + 3) & 0xFFL) << 24;
- result |= (payload.get(index + 2) & 0xFFL) << 16;
- result |= (payload.get(index + 1) & 0xFFL) << 8;
- result |= (payload.get(index + 0) & 0xFFL);
- index += 8;
- return result;
- }
- public long getUnsignedLong(){
- return getLong();
- }
-
- public long getLongReverse() {
- long result = 0;
- result |= (payload.get(index + 0) & 0xFFL) << 56;
- result |= (payload.get(index + 1) & 0xFFL) << 48;
- result |= (payload.get(index + 2) & 0xFFL) << 40;
- result |= (payload.get(index + 3) & 0xFFL) << 32;
- result |= (payload.get(index + 4) & 0xFFL) << 24;
- result |= (payload.get(index + 5) & 0xFFL) << 16;
- result |= (payload.get(index + 6) & 0xFFL) << 8;
- result |= (payload.get(index + 7) & 0xFFL);
- index += 8;
- return result;
- }
- public float getFloat() {
- return Float.intBitsToFloat(getInt());
- }
-
- public void putByte(byte data) {
- add(data);
- }
- public void putUnsignedByte(short data){
- if(data < UNSIGNED_BYTE_MIN_VALUE || data > UNSIGNED_BYTE_MAX_VALUE){
- throw new IllegalArgumentException("Value is outside of the range of an unsigned byte: " + data);
- }
- putByte((byte) data);
- }
- public void putShort(short data) {
- add((byte) (data >> 0));
- add((byte) (data >> 8));
- }
- public void putUnsignedShort(int data){
- if(data < UNSIGNED_SHORT_MIN_VALUE || data > UNSIGNED_SHORT_MAX_VALUE){
- throw new IllegalArgumentException("Value is outside of the range of an unsigned short: " + data);
- }
- putShort((short) data);
- }
- public void putInt(int data) {
- add((byte) (data >> 0));
- add((byte) (data >> 8));
- add((byte) (data >> 16));
- add((byte) (data >> 24));
- }
- public void putUnsignedInt(long data){
- if(data < UNSIGNED_INT_MIN_VALUE || data > UNSIGNED_INT_MAX_VALUE){
- throw new IllegalArgumentException("Value is outside of the range of an unsigned int: " + data);
- }
- putInt((int) data);
- }
- public void putLong(long data) {
- add((byte) (data >> 0));
- add((byte) (data >> 8));
- add((byte) (data >> 16));
- add((byte) (data >> 24));
- add((byte) (data >> 32));
- add((byte) (data >> 40));
- add((byte) (data >> 48));
- add((byte) (data >> 56));
- }
- public void putUnsignedLong(long data){
- if(data < UNSIGNED_LONG_MIN_VALUE){
- throw new IllegalArgumentException("Value is outside of the range of an unsigned long: " + data);
- }
- putLong(data);
- }
- public void putFloat(float data) {
- putInt(Float.floatToIntBits(data));
- }
- }
|