/* AUTO-GENERATED FILE. DO NOT MODIFY. * * This class was automatically generated by the * java mavlink generator tool. It should not be modified by hand. */ // MESSAGE HOME_POSITION PACKING package com.MAVLink.common; import com.MAVLink.MAVLinkPacket; import com.MAVLink.Parser; import com.MAVLink.ardupilotmega.CRC; import java.nio.ByteBuffer; import org.junit.Test; import static org.junit.Assert.assertArrayEquals; /** * This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. */ public class msg_home_position_test{ public static final int MAVLINK_MSG_ID_HOME_POSITION = 242; public static final int MAVLINK_MSG_LENGTH = 52; private static final long serialVersionUID = MAVLINK_MSG_ID_HOME_POSITION; private Parser parser = new Parser(); public CRC generateCRC(byte[] packet){ CRC crc = new CRC(); for (int i = 1; i < packet.length - 2; i++) { crc.update_checksum(packet[i] & 0xFF); } crc.finish_checksum(MAVLINK_MSG_ID_HOME_POSITION); return crc; } public byte[] generateTestPacket(){ ByteBuffer payload = ByteBuffer.allocate(6 + MAVLINK_MSG_LENGTH + 2); payload.put((byte)MAVLinkPacket.MAVLINK_STX); //stx payload.put((byte)MAVLINK_MSG_LENGTH); //len payload.put((byte)0); //seq payload.put((byte)255); //sysid payload.put((byte)190); //comp id payload.put((byte)MAVLINK_MSG_ID_HOME_POSITION); //msg id payload.putInt((int)963497464); //latitude payload.putInt((int)963497672); //longitude payload.putInt((int)963497880); //altitude payload.putFloat((float)101.0); //x payload.putFloat((float)129.0); //y payload.putFloat((float)157.0); //z //q payload.putFloat((float)185.0); payload.putFloat((float)186.0); payload.putFloat((float)187.0); payload.putFloat((float)188.0); payload.putFloat((float)297.0); //approach_x payload.putFloat((float)325.0); //approach_y payload.putFloat((float)353.0); //approach_z CRC crc = generateCRC(payload.array()); payload.put((byte)crc.getLSB()); payload.put((byte)crc.getMSB()); return payload.array(); } @Test public void test(){ byte[] packet = generateTestPacket(); for(int i = 0; i < packet.length - 1; i++){ parser.mavlink_parse_char(packet[i] & 0xFF); } MAVLinkPacket m = parser.mavlink_parse_char(packet[packet.length - 1] & 0xFF); byte[] processedPacket = m.encodePacket(); assertArrayEquals("msg_home_position", processedPacket, packet); } }