/* 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 DIGICAM_CONTROL PACKING package com.MAVLink.ardupilotmega; 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; /** * Control on-board Camera Control System to take shots. */ public class msg_digicam_control_test{ public static final int MAVLINK_MSG_ID_DIGICAM_CONTROL = 155; public static final int MAVLINK_MSG_LENGTH = 13; private static final long serialVersionUID = MAVLINK_MSG_ID_DIGICAM_CONTROL; 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_DIGICAM_CONTROL); 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_DIGICAM_CONTROL); //msg id payload.putFloat((float)17.0); //extra_value payload.put((byte)17); //target_system payload.put((byte)84); //target_component payload.put((byte)151); //session payload.put((byte)218); //zoom_pos payload.put((byte)29); //zoom_step payload.put((byte)96); //focus_lock payload.put((byte)163); //shot payload.put((byte)230); //command_id payload.put((byte)41); //extra_param 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_digicam_control", processedPacket, packet); } }