/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[8 + 21]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFE); dos.writeByte(length & 0x00FF); dos.writeByte(sequence & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeFloat(roll); dos.writeFloat(pitch); dos.writeFloat(yaw); dos.writeFloat(thrust); dos.writeByte(target & 0x00FF); dos.writeByte(roll_manual & 0x00FF); dos.writeByte(pitch_manual & 0x00FF); dos.writeByte(yaw_manual & 0x00FF); dos.writeByte(thrust_manual & 0x00FF); dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 21); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[27] = crcl; buffer[28] = crch; dos.close(); return buffer; }
/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[8 + 12]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFE); dos.writeByte(length & 0x00FF); dos.writeByte(sequence & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeShort(adc1 & 0x00FFFF); dos.writeShort(adc2 & 0x00FFFF); dos.writeShort(adc3 & 0x00FFFF); dos.writeShort(adc4 & 0x00FFFF); dos.writeShort(adc5 & 0x00FFFF); dos.writeShort(adc6 & 0x00FFFF); dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 12); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[18] = crcl; buffer[19] = crch; return buffer; }
/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[12 + 2]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFD); dos.writeByte(length & 0x00FF); dos.writeByte(incompat & 0x00FF); dos.writeByte(compat & 0x00FF); dos.writeByte(packet & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeByte((messageType >> 8) & 0x00FF); dos.writeByte((messageType >> 16) & 0x00FF); dos.writeByte(target_system & 0x00FF); dos.writeByte(target_component & 0x00FF); dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 2); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[12] = crcl; buffer[13] = crch; dos.close(); return buffer; }
/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[8 + 43]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFE); dos.writeByte(length & 0x00FF); dos.writeByte(sequence & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeFloat(x); dos.writeFloat(y); dos.writeFloat(z); dos.writeShort(timeout & 0x00FFFF); dos.writeByte(type & 0x00FF); dos.writeByte(color & 0x00FF); dos.writeByte(coordinate_system & 0x00FF); for (int i = 0; i < 26; i++) { dos.writeByte(name[i]); } dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 43); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[49] = crcl; buffer[50] = crch; dos.close(); return buffer; }
/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[12 + 28]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFD); dos.writeByte(length & 0x00FF); dos.writeByte(incompat & 0x00FF); dos.writeByte(compat & 0x00FF); dos.writeByte(packet & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeByte((messageType >> 8) & 0x00FF); dos.writeByte((messageType >> 16) & 0x00FF); dos.writeInt((int) (time_boot_ms & 0x00FFFFFFFF)); dos.writeFloat(x); dos.writeFloat(y); dos.writeFloat(z); dos.writeFloat(roll); dos.writeFloat(pitch); dos.writeFloat(yaw); dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 28); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[38] = crcl; buffer[39] = crch; dos.close(); return buffer; }
/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[8 + 13]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFE); dos.writeByte(length & 0x00FF); dos.writeByte(sequence & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeInt((int) (latitude & 0x00FFFFFFFF)); dos.writeInt((int) (longitude & 0x00FFFFFFFF)); dos.writeInt((int) (altitude & 0x00FFFFFFFF)); dos.writeByte(target_system & 0x00FF); dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 13); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[19] = crcl; buffer[20] = crch; dos.close(); return buffer; }
/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[8 + 16]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFE); dos.writeByte(length & 0x00FF); dos.writeByte(sequence & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeLong(time_usec); dos.writeShort(press_abs & 0x00FFFF); dos.writeShort(press_diff1 & 0x00FFFF); dos.writeShort(press_diff2 & 0x00FFFF); dos.writeShort(temperature & 0x00FFFF); dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 16); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[22] = crcl; buffer[23] = crch; dos.close(); return buffer; }
/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[8 + 35]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFE); dos.writeByte(length & 0x00FF); dos.writeByte(sequence & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeFloat(param1); dos.writeFloat(param2); dos.writeFloat(param3); dos.writeFloat(param4); dos.writeInt((int) (x & 0x00FFFFFFFF)); dos.writeInt((int) (y & 0x00FFFFFFFF)); dos.writeFloat(z); dos.writeShort(command & 0x00FFFF); dos.writeByte(target_system & 0x00FF); dos.writeByte(target_component & 0x00FF); dos.writeByte(frame & 0x00FF); dos.writeByte(current & 0x00FF); dos.writeByte(autocontinue & 0x00FF); dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 35); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[41] = crcl; buffer[42] = crch; dos.close(); return buffer; }
/** Encode message with raw data and other informations */ public byte[] encode() throws IOException { byte[] buffer = new byte[12 + 23]; LittleEndianDataOutputStream dos = new LittleEndianDataOutputStream(new ByteArrayOutputStream()); dos.writeByte((byte) 0xFD); dos.writeByte(length & 0x00FF); dos.writeByte(incompat & 0x00FF); dos.writeByte(compat & 0x00FF); dos.writeByte(packet & 0x00FF); dos.writeByte(sysId & 0x00FF); dos.writeByte(componentId & 0x00FF); dos.writeByte(messageType & 0x00FF); dos.writeByte((messageType >> 8) & 0x00FF); dos.writeByte((messageType >> 16) & 0x00FF); dos.writeInt((int) (time_boot_ms & 0x00FFFFFFFF)); dos.writeFloat(image_interval); dos.writeFloat(video_framerate); dos.writeShort(image_resolution_h & 0x00FFFF); dos.writeShort(image_resolution_v & 0x00FFFF); dos.writeShort(video_resolution_h & 0x00FFFF); dos.writeShort(video_resolution_v & 0x00FFFF); dos.writeByte(camera_id & 0x00FF); dos.writeByte(image_status & 0x00FF); dos.writeByte(video_status & 0x00FF); dos.flush(); byte[] tmp = dos.toByteArray(); for (int b = 0; b < tmp.length; b++) buffer[b] = tmp[b]; int crc = MAVLinkCRC.crc_calculate_encode(buffer, 23); crc = MAVLinkCRC.crc_accumulate((byte) IMAVLinkCRC.MAVLINK_MESSAGE_CRCS[messageType], crc); byte crcl = (byte) (crc & 0x00FF); byte crch = (byte) ((crc >> 8) & 0x00FF); buffer[33] = crcl; buffer[34] = crch; dos.close(); return buffer; }