/* 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 PARAM_VALUE 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; /** * Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. */ public class msg_param_value_test{ public static final int MAVLINK_MSG_ID_PARAM_VALUE = 22; public static final int MAVLINK_MSG_LENGTH = 25; private static final long serialVersionUID = MAVLINK_MSG_ID_PARAM_VALUE; 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_PARAM_VALUE); 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_PARAM_VALUE); //msg id payload.putFloat((float)17.0); //param_value payload.putShort((short)17443); //param_count payload.putShort((short)17547); //param_index //param_id payload.put((byte)'I'); payload.put((byte)'J'); payload.put((byte)'K'); payload.put((byte)'L'); payload.put((byte)'M'); payload.put((byte)'N'); payload.put((byte)'O'); payload.put((byte)'P'); payload.put((byte)'Q'); payload.put((byte)'R'); payload.put((byte)'S'); payload.put((byte)'T'); payload.put((byte)'U'); payload.put((byte)'V'); payload.put((byte)'W'); payload.put((byte)'I'); payload.put((byte)77); //param_type 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_param_value", processedPacket, packet); } }