MAVLinkPayload.java
Go to the documentation of this file.
00001 /* AUTO-GENERATED FILE.  DO NOT MODIFY.
00002  *
00003  * This class was automatically generated by the
00004  * java mavlink generator tool. It should not be modified by hand.
00005  */
00006 
00007 package com.MAVLink.Messages;
00008 
00009 import java.nio.ByteBuffer;
00010 
00011 public class MAVLinkPayload {
00012 
00013     private static final byte UNSIGNED_BYTE_MIN_VALUE = 0;
00014     private static final short UNSIGNED_BYTE_MAX_VALUE = Byte.MAX_VALUE - Byte.MIN_VALUE;
00015 
00016     private static final short UNSIGNED_SHORT_MIN_VALUE = 0;
00017     private static final int UNSIGNED_SHORT_MAX_VALUE = Short.MAX_VALUE - Short.MIN_VALUE;
00018 
00019     private static final int UNSIGNED_INT_MIN_VALUE = 0;
00020     private static final long UNSIGNED_INT_MAX_VALUE = (long) Integer.MAX_VALUE - Integer.MIN_VALUE;
00021 
00022     private static final long UNSIGNED_LONG_MIN_VALUE = 0;
00023 
00024     public static final int MAX_PAYLOAD_SIZE = 512;
00025     
00026     public final ByteBuffer payload;
00027     public int index;
00028 
00029     public MAVLinkPayload() {
00030         payload = ByteBuffer.allocate(MAX_PAYLOAD_SIZE);
00031     }
00032 
00033     public ByteBuffer getData() {
00034         return payload;
00035     }
00036 
00037     public int size() {
00038         return payload.position();
00039     }
00040 
00041     public void add(byte c) {
00042         payload.put(c);
00043     }
00044 
00045     public void resetIndex() {
00046         index = 0;
00047     }
00048 
00049     public byte getByte() {
00050         byte result = 0;
00051         result |= (payload.get(index + 0) & 0xFF);
00052         index += 1;
00053         return result;
00054     }
00055 
00056     public short getUnsignedByte(){
00057         short result = 0;
00058         result |= payload.get(index + 0) & 0xFF;
00059         index+= 1;
00060         return result; 
00061     }
00062 
00063     public short getShort() {
00064         short result = 0;
00065         result |= (payload.get(index + 1) & 0xFF) << 8;
00066         result |= (payload.get(index + 0) & 0xFF);
00067         index += 2;
00068         return result;
00069     }
00070 
00071     public int getUnsignedShort(){
00072         int result = 0;
00073         result |= (payload.get(index + 1) & 0xFF) << 8;
00074         result |= (payload.get(index + 0) & 0xFF);
00075         index += 2;
00076         return result;
00077     }
00078 
00079     public int getInt() {
00080         int result = 0;
00081         result |= (payload.get(index + 3) & 0xFF) << 24;
00082         result |= (payload.get(index + 2) & 0xFF) << 16;
00083         result |= (payload.get(index + 1) & 0xFF) << 8;
00084         result |= (payload.get(index + 0) & 0xFF);
00085         index += 4;
00086         return result;
00087     }
00088 
00089     public long getUnsignedInt(){
00090         long result = 0;
00091         result |= (payload.get(index + 3) & 0xFFFFL) << 24;
00092         result |= (payload.get(index + 2) & 0xFFFFL) << 16;
00093         result |= (payload.get(index + 1) & 0xFFFFL) << 8;
00094         result |= (payload.get(index + 0) & 0xFFFFL);
00095         index += 4;
00096         return result;
00097     }
00098 
00099     public long getLong() {
00100         long result = 0;
00101         result |= (payload.get(index + 7) & 0xFFFFL) << 56;
00102         result |= (payload.get(index + 6) & 0xFFFFL) << 48;
00103         result |= (payload.get(index + 5) & 0xFFFFL) << 40;
00104         result |= (payload.get(index + 4) & 0xFFFFL) << 32;
00105         result |= (payload.get(index + 3) & 0xFFFFL) << 24;
00106         result |= (payload.get(index + 2) & 0xFFFFL) << 16;
00107         result |= (payload.get(index + 1) & 0xFFFFL) << 8;
00108         result |= (payload.get(index + 0) & 0xFFFFL);
00109         index += 8;
00110         return result;
00111     }
00112 
00113     public long getUnsignedLong(){
00114         return getLong();
00115     }
00116     
00117     public long getLongReverse() {
00118         long result = 0;
00119         result |= (payload.get(index + 0) & 0xFFFFL) << 56;
00120         result |= (payload.get(index + 1) & 0xFFFFL) << 48;
00121         result |= (payload.get(index + 2) & 0xFFFFL) << 40;
00122         result |= (payload.get(index + 3) & 0xFFFFL) << 32;
00123         result |= (payload.get(index + 4) & 0xFFFFL) << 24;
00124         result |= (payload.get(index + 5) & 0xFFFFL) << 16;
00125         result |= (payload.get(index + 6) & 0xFFFFL) << 8;
00126         result |= (payload.get(index + 7) & 0xFFFFL);
00127         index += 8;
00128         return result;
00129     }
00130 
00131     public float getFloat() {
00132         return Float.intBitsToFloat(getInt());
00133     }
00134     
00135     public void putByte(byte data) {
00136         add(data);
00137     }
00138 
00139     public void putUnsignedByte(short data){
00140         if(data < UNSIGNED_BYTE_MIN_VALUE || data > UNSIGNED_BYTE_MAX_VALUE){
00141             throw new IllegalArgumentException("Value is outside of the range of an unsigned byte: " + data);
00142         }
00143 
00144         putByte((byte) data);
00145     }
00146 
00147     public void putShort(short data) {
00148         add((byte) (data >> 0));
00149         add((byte) (data >> 8));
00150     }
00151 
00152     public void putUnsignedShort(int data){
00153         if(data < UNSIGNED_SHORT_MIN_VALUE || data > UNSIGNED_SHORT_MAX_VALUE){
00154             throw new IllegalArgumentException("Value is outside of the range of an unsigned short: " + data);
00155         }
00156 
00157         putShort((short) data);
00158     }
00159 
00160     public void putInt(int data) {
00161         add((byte) (data >> 0));
00162         add((byte) (data >> 8));
00163         add((byte) (data >> 16));
00164         add((byte) (data >> 24));
00165     }
00166 
00167     public void putUnsignedInt(long data){
00168         if(data < UNSIGNED_INT_MIN_VALUE || data > UNSIGNED_INT_MAX_VALUE){
00169             throw new IllegalArgumentException("Value is outside of the range of an unsigned int: " + data);
00170         }
00171 
00172         putInt((int) data);
00173     }
00174 
00175     public void putLong(long data) {
00176         add((byte) (data >> 0));
00177         add((byte) (data >> 8));
00178         add((byte) (data >> 16));
00179         add((byte) (data >> 24));
00180         add((byte) (data >> 32));
00181         add((byte) (data >> 40));
00182         add((byte) (data >> 48));
00183         add((byte) (data >> 56));
00184     }
00185 
00186     public void putUnsignedLong(long data){
00187         if(data < UNSIGNED_LONG_MIN_VALUE){
00188             throw new IllegalArgumentException("Value is outside of the range of an unsigned long: " + data);
00189         }
00190 
00191         putLong(data);
00192     }
00193 
00194     public void putFloat(float data) {
00195         putInt(Float.floatToIntBits(data));
00196     }
00197 
00198 }


mavlink
Author(s): Lorenz Meier
autogenerated on Wed Sep 9 2015 18:06:17