/* 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 NAV_CONTROLLER_OUTPUT 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;
/**
* Outputs of the APM navigation controller. The primary use of this message is to check the response and signs of the controller before actual flight and to assist with tuning controller parameters.
*/
public class msg_nav_controller_output_test{
public static final int MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62;
public static final int MAVLINK_MSG_LENGTH = 26;
private static final long serialVersionUID = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
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_NAV_CONTROLLER_OUTPUT);
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_NAV_CONTROLLER_OUTPUT); //msg id
payload.putFloat((float)17.0); //nav_roll
payload.putFloat((float)45.0); //nav_pitch
payload.putFloat((float)73.0); //alt_error
payload.putFloat((float)101.0); //aspd_error
payload.putFloat((float)129.0); //xtrack_error
payload.putShort((short)18275); //nav_bearing
payload.putShort((short)18379); //target_bearing
payload.putShort((short)18483); //wp_dist
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_nav_controller_output", processedPacket, packet);
}
}