/* 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 HEARTBEAT 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;
/**
* The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).
*/
public class msg_heartbeat_test{
public static final int MAVLINK_MSG_ID_HEARTBEAT = 0;
public static final int MAVLINK_MSG_LENGTH = 9;
private static final long serialVersionUID = MAVLINK_MSG_ID_HEARTBEAT;
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_HEARTBEAT);
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_HEARTBEAT); //msg id
payload.putInt((int)963497464); //custom_mode
payload.put((byte)17); //type
payload.put((byte)84); //autopilot
payload.put((byte)151); //base_mode
payload.put((byte)218); //system_status
payload.put((byte)3); //mavlink_version
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_heartbeat", processedPacket, packet);
}
}