/* 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 SENSOR_OFFSETS 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; /** * Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process. */ public class msg_sensor_offsets_test{ public static final int MAVLINK_MSG_ID_SENSOR_OFFSETS = 150; public static final int MAVLINK_MSG_LENGTH = 42; private static final long serialVersionUID = MAVLINK_MSG_ID_SENSOR_OFFSETS; 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_SENSOR_OFFSETS); 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_SENSOR_OFFSETS); //msg id payload.putFloat((float)17.0); //mag_declination payload.putInt((int)963497672); //raw_press payload.putInt((int)963497880); //raw_temp payload.putFloat((float)101.0); //gyro_cal_x payload.putFloat((float)129.0); //gyro_cal_y payload.putFloat((float)157.0); //gyro_cal_z payload.putFloat((float)185.0); //accel_cal_x payload.putFloat((float)213.0); //accel_cal_y payload.putFloat((float)241.0); //accel_cal_z payload.putShort((short)19107); //mag_ofs_x payload.putShort((short)19211); //mag_ofs_y payload.putShort((short)19315); //mag_ofs_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_sensor_offsets", processedPacket, packet); } }