diff --git a/generate.sh b/generate.sh
index 068bd4a21067f86684277ec7a95ba659a336fd72..38bfd34e4234c285d00dd5c07d421e20c57281f2 100755
--- a/generate.sh
+++ b/generate.sh
@@ -1,4 +1,4 @@
 cd  mavlink
 python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=../mavlink_lib ../message_definitions/lyra.xml
 python3 -m pymavlink.tools.mavgen --lang=Python --wire-protocol=1.0 --output=../mavlink_lib ../message_definitions/lyra.xml
-python3 -m pymavlink.tools.mavgen --lang=JavaScript_NextGen --wire-protocol=1.0 --output=../mavlink_lib_js ../message_definitions/lyra.xml
\ No newline at end of file
+python3 -m pymavlink.tools.mavgen --lang=JavaScript_NextGen --wire-protocol=1.0 --output=../mavlink_lib ../message_definitions/lyra.xml
\ No newline at end of file
diff --git a/mavlink_lib.js b/mavlink_lib.js
new file mode 100644
index 0000000000000000000000000000000000000000..fed66e2cd33a1b01d14169d18d363d0843dbe900
--- /dev/null
+++ b/mavlink_lib.js
@@ -0,0 +1,3144 @@
+/*
+MAVLink protocol implementation for node.js (auto-generated by mavgen_javascript.py)
+
+Generated from: lyra.xml
+
+Note: this file has been auto-generated. DO NOT EDIT
+*/
+
+jspack = require("jspack").jspack,
+    _ = require("underscore"),
+    events = require("events"), // for .emit(..), MAVLink20Processor inherits from events.EventEmitter
+    util = require("util");
+
+var Long = require('long');
+
+// Add a convenience method to Buffer
+Buffer.prototype.toByteArray = function () {
+  return Array.prototype.slice.call(this, 0)
+}
+
+mavlink10 = function(){};
+
+// Implement the CRC-16/MCRF4XX function (present in the Python version through the mavutil.py package)
+mavlink10.x25Crc = function(buffer, crcIN) {
+
+    var bytes = buffer;
+    var crcOUT = crcIN || 0xffff;
+    _.each(bytes, function(e) {
+        var tmp = e ^ (crcOUT & 0xff);
+        tmp = (tmp ^ (tmp << 4)) & 0xff;
+        crcOUT = (crcOUT >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4);
+        crcOUT = crcOUT & 0xffff;
+    });
+    return crcOUT;
+
+}
+
+mavlink10.WIRE_PROTOCOL_VERSION = "1.0";
+mavlink10.PROTOCOL_MARKER_V1 = 0xFE 
+mavlink10.PROTOCOL_MARKER_V2 = 0xFD 
+mavlink10.HEADER_LEN_V1 = 6 
+mavlink10.HEADER_LEN_V2 = 10 
+mavlink10.HEADER_LEN = 6;
+
+mavlink10.MAVLINK_TYPE_CHAR     = 0
+mavlink10.MAVLINK_TYPE_UINT8_T  = 1
+mavlink10.MAVLINK_TYPE_INT8_T   = 2
+mavlink10.MAVLINK_TYPE_UINT16_T = 3
+mavlink10.MAVLINK_TYPE_INT16_T  = 4
+mavlink10.MAVLINK_TYPE_UINT32_T = 5
+mavlink10.MAVLINK_TYPE_INT32_T  = 6
+mavlink10.MAVLINK_TYPE_UINT64_T = 7
+mavlink10.MAVLINK_TYPE_INT64_T  = 8
+mavlink10.MAVLINK_TYPE_FLOAT    = 9
+mavlink10.MAVLINK_TYPE_DOUBLE   = 10
+
+mavlink10.MAVLINK_IFLAG_SIGNED = 0x01
+mavlink10.MAVLINK_SIGNATURE_BLOCK_LEN = 13
+
+// Mavlink headers incorporate sequence, source system (platform) and source component. 
+mavlink10.header = function(msgId, mlen, seq, srcSystem, srcComponent, incompat_flags=0, compat_flags=0,) {
+
+    this.mlen = ( typeof mlen === 'undefined' ) ? 0 : mlen;
+    this.seq = ( typeof seq === 'undefined' ) ? 0 : seq;
+    this.srcSystem = ( typeof srcSystem === 'undefined' ) ? 0 : srcSystem;
+    this.srcComponent = ( typeof srcComponent === 'undefined' ) ? 0 : srcComponent;
+    this.msgId = msgId
+    this.incompat_flags = incompat_flags
+    this.compat_flags = compat_flags
+
+}
+
+mavlink10.header.prototype.pack = function() {
+    return jspack.Pack('BBBBBB', [254, this.mlen, this.seq, this.srcSystem, this.srcComponent, this.msgId]);
+}
+        
+// Base class declaration: mavlink.message will be the parent class for each
+// concrete implementation in mavlink.messages.
+mavlink10.message = function() {};
+
+// Convenience setter to facilitate turning the unpacked array of data into member properties
+mavlink10.message.prototype.set = function(args,verbose) {
+// inspect
+    _.each(this.fieldnames, function(e, i) {
+        var num = parseInt(i,10);
+        if (this.hasOwnProperty(e) && isNaN(num)  ){ // asking for an attribute that's non-numeric is ok unless its already an attribute we have
+            if ( verbose >= 1) { console.log("WARNING, overwriting an existing property is DANGEROUS:"+e+" ==>"+i+"==>"+args[i]+" -> "+JSON.stringify(this)); }
+        }
+    }, this);
+                    //console.log(this.fieldnames);
+// then modify
+    _.each(this.fieldnames, function(e, i) {
+        this[e] = args[i];
+    }, this);
+};
+
+// trying to be the same-ish as the python function of the same name
+mavlink10.message.prototype.sign_packet = function( mav) {
+    var crypto= require('crypto');
+    var h =  crypto.createHash('sha256');
+
+    //mav.signing.timestamp is a 48bit number, or 6 bytes.
+
+        // due to js not being able to shift numbers  more than 32, we'll use this instead.. 
+        // js stores all its numbers as a 64bit float with 53 bits of mantissa, so have room for 48 ok. 
+        // positive shifts left, negative shifts right
+        function shift(number, shift) { 
+            return number * Math.pow(2, shift); 
+        } 
+
+    var thigh = shift(mav.signing.timestamp,-32) // 2 bytes from the top, shifted right by 32 bits
+    var tlow  = (mav.signing.timestamp & 0xfffffff )  // 4 bytes from the bottom
+
+    // I means unsigned 4bytes, H means unsigned 2 bytes
+    // first add the linkid(1 byte) and timestamp(6 bytes) that start the signature
+    this._msgbuf = this._msgbuf.concat(jspack.Pack('<BIH', [mav.signing.link_id, tlow, thigh  ] ) );
+ 
+    h.update(mav.signing.secret_key); // secret is already a Buffer
+    h.update(new Buffer.from(this._msgbuf));
+    var hashDigest = h.digest();
+    sig = hashDigest.slice(0,6)
+    this._msgbuf  = this._msgbuf.concat( ... sig ); 
+
+    mav.signing.timestamp += 1
+} 
+
+
+// This pack function builds the header and produces a complete MAVLink message,
+// including header and message CRC.
+mavlink10.message.prototype.pack = function(mav, crc_extra, payload) {
+
+    this._payload = payload;
+    var plen = this._payload.length;
+// signing is our first incompat flag. 
+    var incompat_flags = 0; 
+    if (mav.signing.sign_outgoing){ 
+            incompat_flags |= mavlink10.MAVLINK_IFLAG_SIGNED 
+    } 
+    // header 
+    this._header = new mavlink10.header(this._id, this._payload.length, mav.seq, mav.srcSystem, mav.srcComponent, incompat_flags, 0,);
+    // payload     
+    this._msgbuf = this._header.pack().concat(this._payload);
+    // crc -  for now, assume always using crc_extra = True.  TODO: check/fix this. 
+    var crc = mavlink10.x25Crc(this._msgbuf.slice(1));
+    crc = mavlink10.x25Crc([crc_extra], crc);
+    this._msgbuf = this._msgbuf.concat(jspack.Pack('<H', [crc] ) );
+
+    // signing 
+    this._signed     = false 
+    this._link_id    = undefined 
+
+    //console.log(mav.signing); 
+    //optionally add signing 
+    if (mav.signing.sign_outgoing){ 
+                this.sign_packet(mav) 
+    } 
+    return this._msgbuf;
+
+}
+
+
+// enums
+
+// SysIDs
+mavlink10.MAV_SYSID_MAIN = 1 // 
+mavlink10.MAV_SYSID_PAYLOAD = 2 // 
+mavlink10.MAV_SYSID_RIG = 3 // 
+mavlink10.MAV_SYSID_GS = 4 // 
+mavlink10.SysIDs_ENUM_END = 5 // 
+
+// SystemTMList
+mavlink10.MAV_SYS_ID = 1 // State of init results about system hardware/software components
+mavlink10.MAV_FSM_ID = 2 // States of all On-Board FSMs
+mavlink10.MAV_PIN_OBS_ID = 3 // Pin observer data
+mavlink10.MAV_LOGGER_ID = 4 // SD Logger stats
+mavlink10.MAV_MAVLINK_STATS = 5 // Mavlink driver stats
+mavlink10.MAV_TASK_STATS_ID = 6 // Task scheduler statistics answer: n mavlink messages where n is the
+                        // number of tasks
+mavlink10.MAV_ADA_ID = 7 // ADA Status
+mavlink10.MAV_NAS_ID = 8 // NavigationSystem data
+mavlink10.MAV_MEA_ID = 9 // MEA Status
+mavlink10.MAV_CAN_ID = 10 // Canbus stats
+mavlink10.MAV_FLIGHT_ID = 11 // Flight telemetry
+mavlink10.MAV_STATS_ID = 12 // Satistics telemetry
+mavlink10.MAV_SENSORS_STATE_ID = 13 // Sensors init state telemetry
+mavlink10.MAV_GSE_ID = 14 // Ground Segnement Equipment
+mavlink10.MAV_MOTOR_ID = 15 // Rocket Motor data
+mavlink10.SystemTMList_ENUM_END = 16 // 
+
+// SensorsTMList
+mavlink10.MAV_GPS_ID = 1 // GPS data
+mavlink10.MAV_BMX160_ID = 2 // BMX160 IMU data
+mavlink10.MAV_VN100_ID = 3 // VN100 IMU data
+mavlink10.MAV_MPU9250_ID = 4 // MPU9250 IMU data
+mavlink10.MAV_ADS_ID = 5 // ADS 8 channel ADC data
+mavlink10.MAV_MS5803_ID = 6 // MS5803 barometer data
+mavlink10.MAV_BME280_ID = 7 // BME280 barometer data
+mavlink10.MAV_CURRENT_SENSE_ID = 8 // Electrical current sensors data
+mavlink10.MAV_LIS3MDL_ID = 9 // LIS3MDL compass data
+mavlink10.MAV_DPL_PRESS_ID = 10 // Deployment pressure data
+mavlink10.MAV_STATIC_PRESS_ID = 11 // Static pressure data
+mavlink10.MAV_PITOT_PRESS_ID = 12 // Pitot pressure data
+mavlink10.MAV_BATTERY_VOLTAGE_ID = 13 // Battery voltage data
+mavlink10.MAV_LOAD_CELL_ID = 14 // Load cell data
+mavlink10.MAV_FILLING_PRESS_ID = 15 // Filling line pressure
+mavlink10.MAV_TANK_TOP_PRESS_ID = 16 // Top tank pressure
+mavlink10.MAV_TANK_BOTTOM_PRESS_ID = 17 // Bottom tank pressure
+mavlink10.MAV_TANK_TEMP_ID = 18 // Tank temperature
+mavlink10.MAV_COMBUSTION_PRESS_ID = 19 // Combustion chamber pressure
+mavlink10.MAV_VESSEL_PRESS_ID = 20 // Vessel pressure
+mavlink10.MAV_LOAD_CELL_VESSEL_ID = 21 // Vessel tank weight
+mavlink10.MAV_LOAD_CELL_TANK_ID = 22 // Tank weight
+mavlink10.MAV_LIS2MDL_ID = 23 // Magnetometer data
+mavlink10.MAV_LPS28DFW_ID = 24 // Pressure sensor data
+mavlink10.MAV_LSM6DSRX_ID = 25 // IMU data
+mavlink10.MAV_H3LIS331DL_ID = 26 // 400G accelerometer
+mavlink10.MAV_LPS22DF_ID = 27 // Pressure sensor data
+mavlink10.SensorsTMList_ENUM_END = 28 // 
+
+// MavCommandList
+mavlink10.MAV_CMD_ARM = 1 // Command to arm the rocket
+mavlink10.MAV_CMD_DISARM = 2 // Command to disarm the rocket
+mavlink10.MAV_CMD_CALIBRATE = 3 // Command to trigger the calibration
+mavlink10.MAV_CMD_SAVE_CALIBRATION = 4 // Command to save the current calibration into a file
+mavlink10.MAV_CMD_FORCE_INIT = 5 // Command to init the rocket
+mavlink10.MAV_CMD_FORCE_LAUNCH = 6 // Command to force the launch state on the rocket
+mavlink10.MAV_CMD_FORCE_LANDING = 7 // Command to communicate the end of the mission and close the file
+                        // descriptors in the SD card
+mavlink10.MAV_CMD_FORCE_APOGEE = 8 // Command to trigger the apogee event
+mavlink10.MAV_CMD_FORCE_EXPULSION = 9 // Command to open the nosecone
+mavlink10.MAV_CMD_FORCE_DEPLOYMENT = 10 // Command to activate the thermal cutters and cut the drogue, activating
+                        // both thermal cutters sequentially
+mavlink10.MAV_CMD_START_LOGGING = 11 // Command to enable sensor logging
+mavlink10.MAV_CMD_STOP_LOGGING = 12 // Command to permanently close the log file
+mavlink10.MAV_CMD_FORCE_REBOOT = 13 // Command to reset the board from test status
+mavlink10.MAV_CMD_ENTER_TEST_MODE = 14 // Command to enter the test mode
+mavlink10.MAV_CMD_EXIT_TEST_MODE = 15 // Command to exit the test mode
+mavlink10.MAV_CMD_START_RECORDING = 16 // Command to start the internal cameras recordings
+mavlink10.MAV_CMD_STOP_RECORDING = 17 // Command to stop the internal cameras recordings
+mavlink10.MavCommandList_ENUM_END = 18 // 
+
+// ServosList
+mavlink10.AIR_BRAKES_SERVO = 1 // 
+mavlink10.EXPULSION_SERVO = 2 // 
+mavlink10.PARAFOIL_LEFT_SERVO = 3 // 
+mavlink10.PARAFOIL_RIGHT_SERVO = 4 // 
+mavlink10.MAIN_VALVE = 5 // 
+mavlink10.VENTING_VALVE = 6 // 
+mavlink10.RELEASE_VALVE = 7 // 
+mavlink10.FILLING_VALVE = 8 // 
+mavlink10.DISCONNECT_SERVO = 9 // 
+mavlink10.ServosList_ENUM_END = 10 // 
+
+// StepperList
+mavlink10.STEPPER_X = 1 // 
+mavlink10.STEPPER_Y = 2 // 
+mavlink10.StepperList_ENUM_END = 3 // 
+
+// PinsList
+mavlink10.LAUNCH_PIN = 1 // 
+mavlink10.NOSECONE_PIN = 2 // 
+mavlink10.DEPLOYMENT_PIN = 3 // 
+mavlink10.QUICK_CONNECTOR_PIN = 4 // 
+mavlink10.PinsList_ENUM_END = 5 // 
+
+// message IDs
+mavlink10.MAVLINK_MSG_ID_BAD_DATA = -1
+mavlink10.MAVLINK_MSG_ID_PING_TC = 1
+mavlink10.MAVLINK_MSG_ID_COMMAND_TC = 2
+mavlink10.MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC = 3
+mavlink10.MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC = 4
+mavlink10.MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC = 5
+mavlink10.MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC = 6
+mavlink10.MAVLINK_MSG_ID_WIGGLE_SERVO_TC = 7
+mavlink10.MAVLINK_MSG_ID_RESET_SERVO_TC = 8
+mavlink10.MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC = 9
+mavlink10.MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC = 10
+mavlink10.MAVLINK_MSG_ID_SET_ORIENTATION_TC = 11
+mavlink10.MAVLINK_MSG_ID_SET_COORDINATES_TC = 12
+mavlink10.MAVLINK_MSG_ID_RAW_EVENT_TC = 13
+mavlink10.MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC = 14
+mavlink10.MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC = 15
+mavlink10.MAVLINK_MSG_ID_SET_ALGORITHM_TC = 16
+mavlink10.MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC = 17
+mavlink10.MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC = 18
+mavlink10.MAVLINK_MSG_ID_CONRIG_STATE_TC = 19
+mavlink10.MAVLINK_MSG_ID_SET_IGNITION_TIME_TC = 20
+mavlink10.MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC = 21
+mavlink10.MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC = 22
+mavlink10.MAVLINK_MSG_ID_ACK_TM = 100
+mavlink10.MAVLINK_MSG_ID_NACK_TM = 101
+mavlink10.MAVLINK_MSG_ID_GPS_TM = 102
+mavlink10.MAVLINK_MSG_ID_IMU_TM = 103
+mavlink10.MAVLINK_MSG_ID_PRESSURE_TM = 104
+mavlink10.MAVLINK_MSG_ID_ADC_TM = 105
+mavlink10.MAVLINK_MSG_ID_VOLTAGE_TM = 106
+mavlink10.MAVLINK_MSG_ID_CURRENT_TM = 107
+mavlink10.MAVLINK_MSG_ID_TEMP_TM = 108
+mavlink10.MAVLINK_MSG_ID_LOAD_TM = 109
+mavlink10.MAVLINK_MSG_ID_ATTITUDE_TM = 110
+mavlink10.MAVLINK_MSG_ID_SENSOR_STATE_TM = 111
+mavlink10.MAVLINK_MSG_ID_SERVO_TM = 112
+mavlink10.MAVLINK_MSG_ID_PIN_TM = 113
+mavlink10.MAVLINK_MSG_ID_RECEIVER_TM = 150
+mavlink10.MAVLINK_MSG_ID_ARP_TM = 169
+mavlink10.MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC = 170
+mavlink10.MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC = 171
+mavlink10.MAVLINK_MSG_ID_SYS_TM = 200
+mavlink10.MAVLINK_MSG_ID_FSM_TM = 201
+mavlink10.MAVLINK_MSG_ID_LOGGER_TM = 202
+mavlink10.MAVLINK_MSG_ID_MAVLINK_STATS_TM = 203
+mavlink10.MAVLINK_MSG_ID_TASK_STATS_TM = 204
+mavlink10.MAVLINK_MSG_ID_ADA_TM = 205
+mavlink10.MAVLINK_MSG_ID_NAS_TM = 206
+mavlink10.MAVLINK_MSG_ID_MEA_TM = 207
+mavlink10.MAVLINK_MSG_ID_ROCKET_FLIGHT_TM = 208
+mavlink10.MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM = 209
+mavlink10.MAVLINK_MSG_ID_ROCKET_STATS_TM = 210
+mavlink10.MAVLINK_MSG_ID_PAYLOAD_STATS_TM = 211
+mavlink10.MAVLINK_MSG_ID_GSE_TM = 212
+mavlink10.MAVLINK_MSG_ID_MOTOR_TM = 213
+mavlink10.messages = {};
+
+
+/* 
+TC to ping the rocket (expects an ACK message as a response)
+
+                timestamp                 : Timestamp to identify when it was sent (uint64_t)
+
+*/
+    mavlink10.messages.ping_tc = function( ...moreargs ) {
+     [ this.timestamp ] = moreargs;
+
+
+    this._format = '<Q';
+    this._id = mavlink10.MAVLINK_MSG_ID_PING_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 136;
+    this._name = 'PING_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp'];
+
+}
+
+mavlink10.messages.ping_tc.prototype = new mavlink10.message;
+mavlink10.messages.ping_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+TC containing a command with no parameters that trigger some action
+
+                command_id                : A member of the MavCommandList enum (uint8_t)
+
+*/
+    mavlink10.messages.command_tc = function( ...moreargs ) {
+     [ this.command_id ] = moreargs;
+
+
+    this._format = '<B';
+    this._id = mavlink10.MAVLINK_MSG_ID_COMMAND_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 198;
+    this._name = 'COMMAND_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['command_id'];
+
+}
+
+mavlink10.messages.command_tc.prototype = new mavlink10.message;
+mavlink10.messages.command_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.command_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+TC containing a request for the status of a board
+
+                tm_id                     : A member of the SystemTMList enum (uint8_t)
+
+*/
+    mavlink10.messages.system_tm_request_tc = function( ...moreargs ) {
+     [ this.tm_id ] = moreargs;
+
+
+    this._format = '<B';
+    this._id = mavlink10.MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 165;
+    this._name = 'SYSTEM_TM_REQUEST_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['tm_id'];
+
+}
+
+mavlink10.messages.system_tm_request_tc.prototype = new mavlink10.message;
+mavlink10.messages.system_tm_request_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.tm_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+TC containing a request for sensors telemetry
+
+                sensor_name               : A member of the SensorTMList enum (uint8_t)
+
+*/
+    mavlink10.messages.sensor_tm_request_tc = function( ...moreargs ) {
+     [ this.sensor_name ] = moreargs;
+
+
+    this._format = '<B';
+    this._id = mavlink10.MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 248;
+    this._name = 'SENSOR_TM_REQUEST_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['sensor_name'];
+
+}
+
+mavlink10.messages.sensor_tm_request_tc.prototype = new mavlink10.message;
+mavlink10.messages.sensor_tm_request_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+TC containing a request for servo telemetry
+
+                servo_id                  : A member of the ServosList enum (uint8_t)
+
+*/
+    mavlink10.messages.servo_tm_request_tc = function( ...moreargs ) {
+     [ this.servo_id ] = moreargs;
+
+
+    this._format = '<B';
+    this._id = mavlink10.MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 184;
+    this._name = 'SERVO_TM_REQUEST_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['servo_id'];
+
+}
+
+mavlink10.messages.servo_tm_request_tc.prototype = new mavlink10.message;
+mavlink10.messages.servo_tm_request_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.servo_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the angle of a certain servo
+
+                servo_id                  : A member of the ServosList enum (uint8_t)
+                angle                     : Servo angle in normalized value [0-1] (float)
+
+*/
+    mavlink10.messages.set_servo_angle_tc = function( ...moreargs ) {
+     [ this.servo_id , this.angle ] = moreargs;
+
+
+    this._format = '<fB';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC;
+    this.order_map = [1, 0];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 215;
+    this._name = 'SET_SERVO_ANGLE_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['servo_id', 'angle'];
+
+}
+
+mavlink10.messages.set_servo_angle_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_servo_angle_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.angle, this.servo_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Wiggles the specified servo
+
+                servo_id                  : A member of the ServosList enum (uint8_t)
+
+*/
+    mavlink10.messages.wiggle_servo_tc = function( ...moreargs ) {
+     [ this.servo_id ] = moreargs;
+
+
+    this._format = '<B';
+    this._id = mavlink10.MAVLINK_MSG_ID_WIGGLE_SERVO_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 160;
+    this._name = 'WIGGLE_SERVO_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['servo_id'];
+
+}
+
+mavlink10.messages.wiggle_servo_tc.prototype = new mavlink10.message;
+mavlink10.messages.wiggle_servo_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.servo_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Resets the specified servo
+
+                servo_id                  : A member of the ServosList enum (uint8_t)
+
+*/
+    mavlink10.messages.reset_servo_tc = function( ...moreargs ) {
+     [ this.servo_id ] = moreargs;
+
+
+    this._format = '<B';
+    this._id = mavlink10.MAVLINK_MSG_ID_RESET_SERVO_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 226;
+    this._name = 'RESET_SERVO_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['servo_id'];
+
+}
+
+mavlink10.messages.reset_servo_tc.prototype = new mavlink10.message;
+mavlink10.messages.reset_servo_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.servo_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the reference altitude for the altimeter
+
+                ref_altitude              : Reference altitude (float)
+
+*/
+    mavlink10.messages.set_reference_altitude_tc = function( ...moreargs ) {
+     [ this.ref_altitude ] = moreargs;
+
+
+    this._format = '<f';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 113;
+    this._name = 'SET_REFERENCE_ALTITUDE_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['ref_altitude'];
+
+}
+
+mavlink10.messages.set_reference_altitude_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_reference_altitude_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.ref_altitude];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the reference temperature for the altimeter
+
+                ref_temp                  : Reference temperature (float)
+
+*/
+    mavlink10.messages.set_reference_temperature_tc = function( ...moreargs ) {
+     [ this.ref_temp ] = moreargs;
+
+
+    this._format = '<f';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 38;
+    this._name = 'SET_REFERENCE_TEMPERATURE_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['ref_temp'];
+
+}
+
+mavlink10.messages.set_reference_temperature_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_reference_temperature_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.ref_temp];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets current orientation for the navigation system
+
+                yaw                       : Yaw angle (float)
+                pitch                     : Pitch angle (float)
+                roll                      : Roll angle (float)
+
+*/
+    mavlink10.messages.set_orientation_tc = function( ...moreargs ) {
+     [ this.yaw , this.pitch , this.roll ] = moreargs;
+
+
+    this._format = '<fff';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_ORIENTATION_TC;
+    this.order_map = [0, 1, 2];
+    this.len_map = [1, 1, 1];
+    this.array_len_map = [0, 0, 0];
+    this.crc_extra = 71;
+    this._name = 'SET_ORIENTATION_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['yaw', 'pitch', 'roll'];
+
+}
+
+mavlink10.messages.set_orientation_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_orientation_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.yaw, this.pitch, this.roll];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets current coordinates
+
+                latitude                  : Latitude (float)
+                longitude                 : Longitude (float)
+
+*/
+    mavlink10.messages.set_coordinates_tc = function( ...moreargs ) {
+     [ this.latitude , this.longitude ] = moreargs;
+
+
+    this._format = '<ff';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_COORDINATES_TC;
+    this.order_map = [0, 1];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 67;
+    this._name = 'SET_COORDINATES_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['latitude', 'longitude'];
+
+}
+
+mavlink10.messages.set_coordinates_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_coordinates_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.latitude, this.longitude];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+TC containing a raw event to be posted directly in the EventBroker
+
+                topic_id                  : Id of the topic to which the event should be posted (uint8_t)
+                event_id                  : Id of the event to be posted (uint8_t)
+
+*/
+    mavlink10.messages.raw_event_tc = function( ...moreargs ) {
+     [ this.topic_id , this.event_id ] = moreargs;
+
+
+    this._format = '<BB';
+    this._id = mavlink10.MAVLINK_MSG_ID_RAW_EVENT_TC;
+    this.order_map = [0, 1];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 218;
+    this._name = 'RAW_EVENT_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['topic_id', 'event_id'];
+
+}
+
+mavlink10.messages.raw_event_tc.prototype = new mavlink10.message;
+mavlink10.messages.raw_event_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.topic_id, this.event_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the deployment altitude for the main parachute
+
+                dpl_altitude              : Deployment altitude (float)
+
+*/
+    mavlink10.messages.set_deployment_altitude_tc = function( ...moreargs ) {
+     [ this.dpl_altitude ] = moreargs;
+
+
+    this._format = '<f';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 44;
+    this._name = 'SET_DEPLOYMENT_ALTITUDE_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['dpl_altitude'];
+
+}
+
+mavlink10.messages.set_deployment_altitude_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_deployment_altitude_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.dpl_altitude];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the target coordinates
+
+                latitude                  : Latitude (float)
+                longitude                 : Longitude (float)
+
+*/
+    mavlink10.messages.set_target_coordinates_tc = function( ...moreargs ) {
+     [ this.latitude , this.longitude ] = moreargs;
+
+
+    this._format = '<ff';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC;
+    this.order_map = [0, 1];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 81;
+    this._name = 'SET_TARGET_COORDINATES_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['latitude', 'longitude'];
+
+}
+
+mavlink10.messages.set_target_coordinates_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_target_coordinates_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.latitude, this.longitude];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the algorithm number (for parafoil guidance and GSE tars)
+
+                algorithm_number          : Algorithm number (uint8_t)
+
+*/
+    mavlink10.messages.set_algorithm_tc = function( ...moreargs ) {
+     [ this.algorithm_number ] = moreargs;
+
+
+    this._format = '<B';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_ALGORITHM_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 181;
+    this._name = 'SET_ALGORITHM_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['algorithm_number'];
+
+}
+
+mavlink10.messages.set_algorithm_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_algorithm_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.algorithm_number];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the maximum time that the valves can be open atomically
+
+                servo_id                  : A member of the ServosList enum (uint8_t)
+                maximum_timing            : Maximum timing in [ms] (uint32_t)
+
+*/
+    mavlink10.messages.set_atomic_valve_timing_tc = function( ...moreargs ) {
+     [ this.servo_id , this.maximum_timing ] = moreargs;
+
+
+    this._format = '<IB';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC;
+    this.order_map = [1, 0];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 110;
+    this._name = 'SET_ATOMIC_VALVE_TIMING_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['servo_id', 'maximum_timing'];
+
+}
+
+mavlink10.messages.set_atomic_valve_timing_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_atomic_valve_timing_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.maximum_timing, this.servo_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the maximum aperture of the specified valve. Set as value from 0
+to 1
+
+                servo_id                  : A member of the ServosList enum (uint8_t)
+                maximum_aperture          : Maximum aperture (float)
+
+*/
+    mavlink10.messages.set_valve_maximum_aperture_tc = function( ...moreargs ) {
+     [ this.servo_id , this.maximum_aperture ] = moreargs;
+
+
+    this._format = '<fB';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC;
+    this.order_map = [1, 0];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 22;
+    this._name = 'SET_VALVE_MAXIMUM_APERTURE_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['servo_id', 'maximum_aperture'];
+
+}
+
+mavlink10.messages.set_valve_maximum_aperture_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_valve_maximum_aperture_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.maximum_aperture, this.servo_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Send the state of the conrig buttons
+
+                ignition_btn              : Ignition button pressed (uint8_t)
+                filling_valve_btn         : Open filling valve pressed (uint8_t)
+                venting_valve_btn         : Open venting valve pressed (uint8_t)
+                release_pressure_btn        : Release filling line pressure pressed (uint8_t)
+                quick_connector_btn        : Detach quick connector pressed (uint8_t)
+                start_tars_btn            : Startup TARS pressed (uint8_t)
+                arm_switch                : Arming switch state (uint8_t)
+
+*/
+    mavlink10.messages.conrig_state_tc = function( ...moreargs ) {
+     [ this.ignition_btn , this.filling_valve_btn , this.venting_valve_btn , this.release_pressure_btn , this.quick_connector_btn , this.start_tars_btn , this.arm_switch ] = moreargs;
+
+
+    this._format = '<BBBBBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_CONRIG_STATE_TC;
+    this.order_map = [0, 1, 2, 3, 4, 5, 6];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 65;
+    this._name = 'CONRIG_STATE_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['ignition_btn', 'filling_valve_btn', 'venting_valve_btn', 'release_pressure_btn', 'quick_connector_btn', 'start_tars_btn', 'arm_switch'];
+
+}
+
+mavlink10.messages.conrig_state_tc.prototype = new mavlink10.message;
+mavlink10.messages.conrig_state_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.ignition_btn, this.filling_valve_btn, this.venting_valve_btn, this.release_pressure_btn, this.quick_connector_btn, this.start_tars_btn, this.arm_switch];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets the time in ms that the igniter stays on before the oxidant valve
+is opened
+
+                timing                    : Timing in [ms] (uint32_t)
+
+*/
+    mavlink10.messages.set_ignition_time_tc = function( ...moreargs ) {
+     [ this.timing ] = moreargs;
+
+
+    this._format = '<I';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_IGNITION_TIME_TC;
+    this.order_map = [0];
+    this.len_map = [1];
+    this.array_len_map = [0];
+    this.crc_extra = 79;
+    this._name = 'SET_IGNITION_TIME_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timing'];
+
+}
+
+mavlink10.messages.set_ignition_time_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_ignition_time_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.timing];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Move the stepper of a certain angle
+
+                stepper_id                : A member of the StepperList enum (uint8_t)
+                angle                     : Stepper angle in degrees (float)
+
+*/
+    mavlink10.messages.set_stepper_angle_tc = function( ...moreargs ) {
+     [ this.stepper_id , this.angle ] = moreargs;
+
+
+    this._format = '<fB';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC;
+    this.order_map = [1, 0];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 180;
+    this._name = 'SET_STEPPER_ANGLE_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['stepper_id', 'angle'];
+
+}
+
+mavlink10.messages.set_stepper_angle_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_stepper_angle_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.angle, this.stepper_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Move the stepper of a certain amount of steps
+
+                stepper_id                : A member of the StepperList enum (uint8_t)
+                steps                     : Number of steps (float)
+
+*/
+    mavlink10.messages.set_stepper_steps_tc = function( ...moreargs ) {
+     [ this.stepper_id , this.steps ] = moreargs;
+
+
+    this._format = '<fB';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC;
+    this.order_map = [1, 0];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 246;
+    this._name = 'SET_STEPPER_STEPS_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['stepper_id', 'steps'];
+
+}
+
+mavlink10.messages.set_stepper_steps_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_stepper_steps_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.steps, this.stepper_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+TM containing an ACK message to notify that the message has been
+received
+
+                recv_msgid                : Message id of the received message (uint8_t)
+                seq_ack                   : Sequence number of the received message (uint8_t)
+
+*/
+    mavlink10.messages.ack_tm = function( ...moreargs ) {
+     [ this.recv_msgid , this.seq_ack ] = moreargs;
+
+
+    this._format = '<BB';
+    this._id = mavlink10.MAVLINK_MSG_ID_ACK_TM;
+    this.order_map = [0, 1];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 50;
+    this._name = 'ACK_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['recv_msgid', 'seq_ack'];
+
+}
+
+mavlink10.messages.ack_tm.prototype = new mavlink10.message;
+mavlink10.messages.ack_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.recv_msgid, this.seq_ack];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+TM containing a NACK message to notify that the received message was
+invalid
+
+                recv_msgid                : Message id of the received message (uint8_t)
+                seq_ack                   : Sequence number of the received message (uint8_t)
+
+*/
+    mavlink10.messages.nack_tm = function( ...moreargs ) {
+     [ this.recv_msgid , this.seq_ack ] = moreargs;
+
+
+    this._format = '<BB';
+    this._id = mavlink10.MAVLINK_MSG_ID_NACK_TM;
+    this.order_map = [0, 1];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 146;
+    this._name = 'NACK_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['recv_msgid', 'seq_ack'];
+
+}
+
+mavlink10.messages.nack_tm.prototype = new mavlink10.message;
+mavlink10.messages.nack_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.recv_msgid, this.seq_ack];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                fix                       : Wether the GPS has a FIX (uint8_t)
+                latitude                  : Latitude (double)
+                longitude                 : Longitude (double)
+                height                    : Altitude (double)
+                vel_north                 : Velocity in NED frame (north) (float)
+                vel_east                  : Velocity in NED frame (east) (float)
+                vel_down                  : Velocity in NED frame (down) (float)
+                speed                     : Speed (float)
+                track                     : Track (float)
+                n_satellites              : Number of connected satellites (uint8_t)
+
+*/
+    mavlink10.messages.gps_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.fix , this.latitude , this.longitude , this.height , this.vel_north , this.vel_east , this.vel_down , this.speed , this.track , this.n_satellites ] = moreargs;
+
+
+    this._format = '<Qdddfffff20sBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_GPS_TM;
+    this.order_map = [0, 9, 10, 1, 2, 3, 4, 5, 6, 7, 8, 11];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 0, 0];
+    this.crc_extra = 57;
+    this._name = 'GPS_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'fix', 'latitude', 'longitude', 'height', 'vel_north', 'vel_east', 'vel_down', 'speed', 'track', 'n_satellites'];
+
+}
+
+mavlink10.messages.gps_tm.prototype = new mavlink10.message;
+mavlink10.messages.gps_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.latitude, this.longitude, this.height, this.vel_north, this.vel_east, this.vel_down, this.speed, this.track, this.sensor_name, this.fix, this.n_satellites];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                acc_x                     : X axis acceleration (float)
+                acc_y                     : Y axis acceleration (float)
+                acc_z                     : Z axis acceleration (float)
+                gyro_x                    : X axis gyro (float)
+                gyro_y                    : Y axis gyro (float)
+                gyro_z                    : Z axis gyro (float)
+                mag_x                     : X axis compass (float)
+                mag_y                     : Y axis compass (float)
+                mag_z                     : Z axis compass (float)
+
+*/
+    mavlink10.messages.imu_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.acc_x , this.acc_y , this.acc_z , this.gyro_x , this.gyro_y , this.gyro_z , this.mag_x , this.mag_y , this.mag_z ] = moreargs;
+
+
+    this._format = '<Qfffffffff20s';
+    this._id = mavlink10.MAVLINK_MSG_ID_IMU_TM;
+    this.order_map = [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20];
+    this.crc_extra = 72;
+    this._name = 'IMU_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z'];
+
+}
+
+mavlink10.messages.imu_tm.prototype = new mavlink10.message;
+mavlink10.messages.imu_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.acc_x, this.acc_y, this.acc_z, this.gyro_x, this.gyro_y, this.gyro_z, this.mag_x, this.mag_y, this.mag_z, this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                pressure                  : Pressure of the digital barometer (float)
+
+*/
+    mavlink10.messages.pressure_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.pressure ] = moreargs;
+
+
+    this._format = '<Qf20s';
+    this._id = mavlink10.MAVLINK_MSG_ID_PRESSURE_TM;
+    this.order_map = [0, 2, 1];
+    this.len_map = [1, 1, 1];
+    this.array_len_map = [0, 0, 20];
+    this.crc_extra = 87;
+    this._name = 'PRESSURE_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'pressure'];
+
+}
+
+mavlink10.messages.pressure_tm.prototype = new mavlink10.message;
+mavlink10.messages.pressure_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.pressure, this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                channel_0                 : ADC voltage measured on channel 0 (float)
+                channel_1                 : ADC voltage measured on channel 1 (float)
+                channel_2                 : ADC voltage measured on channel 2 (float)
+                channel_3                 : ADC voltage measured on channel 3 (float)
+                channel_4                 : ADC voltage measured on channel 4 (float)
+                channel_5                 : ADC voltage measured on channel 5 (float)
+                channel_6                 : ADC voltage measured on channel 6 (float)
+                channel_7                 : ADC voltage measured on channel 7 (float)
+
+*/
+    mavlink10.messages.adc_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.channel_0 , this.channel_1 , this.channel_2 , this.channel_3 , this.channel_4 , this.channel_5 , this.channel_6 , this.channel_7 ] = moreargs;
+
+
+    this._format = '<Qffffffff20s';
+    this._id = mavlink10.MAVLINK_MSG_ID_ADC_TM;
+    this.order_map = [0, 9, 1, 2, 3, 4, 5, 6, 7, 8];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20];
+    this.crc_extra = 229;
+    this._name = 'ADC_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'channel_0', 'channel_1', 'channel_2', 'channel_3', 'channel_4', 'channel_5', 'channel_6', 'channel_7'];
+
+}
+
+mavlink10.messages.adc_tm.prototype = new mavlink10.message;
+mavlink10.messages.adc_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.channel_0, this.channel_1, this.channel_2, this.channel_3, this.channel_4, this.channel_5, this.channel_6, this.channel_7, this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                voltage                   : Voltage (float)
+
+*/
+    mavlink10.messages.voltage_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.voltage ] = moreargs;
+
+
+    this._format = '<Qf20s';
+    this._id = mavlink10.MAVLINK_MSG_ID_VOLTAGE_TM;
+    this.order_map = [0, 2, 1];
+    this.len_map = [1, 1, 1];
+    this.array_len_map = [0, 0, 20];
+    this.crc_extra = 245;
+    this._name = 'VOLTAGE_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'voltage'];
+
+}
+
+mavlink10.messages.voltage_tm.prototype = new mavlink10.message;
+mavlink10.messages.voltage_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.voltage, this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                current                   : Current (float)
+
+*/
+    mavlink10.messages.current_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.current ] = moreargs;
+
+
+    this._format = '<Qf20s';
+    this._id = mavlink10.MAVLINK_MSG_ID_CURRENT_TM;
+    this.order_map = [0, 2, 1];
+    this.len_map = [1, 1, 1];
+    this.array_len_map = [0, 0, 20];
+    this.crc_extra = 212;
+    this._name = 'CURRENT_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'current'];
+
+}
+
+mavlink10.messages.current_tm.prototype = new mavlink10.message;
+mavlink10.messages.current_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.current, this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                temperature               : Temperature (float)
+
+*/
+    mavlink10.messages.temp_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.temperature ] = moreargs;
+
+
+    this._format = '<Qf20s';
+    this._id = mavlink10.MAVLINK_MSG_ID_TEMP_TM;
+    this.order_map = [0, 2, 1];
+    this.len_map = [1, 1, 1];
+    this.array_len_map = [0, 0, 20];
+    this.crc_extra = 140;
+    this._name = 'TEMP_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'temperature'];
+
+}
+
+mavlink10.messages.temp_tm.prototype = new mavlink10.message;
+mavlink10.messages.temp_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.temperature, this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                load                      : Load force (float)
+
+*/
+    mavlink10.messages.load_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.load ] = moreargs;
+
+
+    this._format = '<Qf20s';
+    this._id = mavlink10.MAVLINK_MSG_ID_LOAD_TM;
+    this.order_map = [0, 2, 1];
+    this.len_map = [1, 1, 1];
+    this.array_len_map = [0, 0, 20];
+    this.crc_extra = 148;
+    this._name = 'LOAD_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'load'];
+
+}
+
+mavlink10.messages.load_tm.prototype = new mavlink10.message;
+mavlink10.messages.load_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.load, this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : When was this logged (uint64_t)
+                sensor_name               : Sensor name (char)
+                roll                      : Roll angle (float)
+                pitch                     : Pitch angle (float)
+                yaw                       : Yaw angle (float)
+                quat_x                    : Quaternion x component (float)
+                quat_y                    : Quaternion y component (float)
+                quat_z                    : Quaternion z component (float)
+                quat_w                    : Quaternion w component (float)
+
+*/
+    mavlink10.messages.attitude_tm = function( ...moreargs ) {
+     [ this.timestamp , this.sensor_name , this.roll , this.pitch , this.yaw , this.quat_x , this.quat_y , this.quat_z , this.quat_w ] = moreargs;
+
+
+    this._format = '<Qfffffff20s';
+    this._id = mavlink10.MAVLINK_MSG_ID_ATTITUDE_TM;
+    this.order_map = [0, 8, 1, 2, 3, 4, 5, 6, 7];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 20];
+    this.crc_extra = 6;
+    this._name = 'ATTITUDE_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'sensor_name', 'roll', 'pitch', 'yaw', 'quat_x', 'quat_y', 'quat_z', 'quat_w'];
+
+}
+
+mavlink10.messages.attitude_tm.prototype = new mavlink10.message;
+mavlink10.messages.attitude_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.roll, this.pitch, this.yaw, this.quat_x, this.quat_y, this.quat_z, this.quat_w, this.sensor_name];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                sensor_name               : Sensor name (char)
+                state                     : Boolean that represents the init state (uint8_t)
+
+*/
+    mavlink10.messages.sensor_state_tm = function( ...moreargs ) {
+     [ this.sensor_name , this.state ] = moreargs;
+
+
+    this._format = '<20sB';
+    this._id = mavlink10.MAVLINK_MSG_ID_SENSOR_STATE_TM;
+    this.order_map = [0, 1];
+    this.len_map = [1, 1];
+    this.array_len_map = [20, 0];
+    this.crc_extra = 155;
+    this._name = 'SENSOR_STATE_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['sensor_name', 'state'];
+
+}
+
+mavlink10.messages.sensor_state_tm.prototype = new mavlink10.message;
+mavlink10.messages.sensor_state_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.sensor_name, this.state];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                servo_id                  : A member of the ServosList enum (uint8_t)
+                servo_position            : Position of the servo [0-1] (float)
+
+*/
+    mavlink10.messages.servo_tm = function( ...moreargs ) {
+     [ this.servo_id , this.servo_position ] = moreargs;
+
+
+    this._format = '<fB';
+    this._id = mavlink10.MAVLINK_MSG_ID_SERVO_TM;
+    this.order_map = [1, 0];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 87;
+    this._name = 'SERVO_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['servo_id', 'servo_position'];
+
+}
+
+mavlink10.messages.servo_tm.prototype = new mavlink10.message;
+mavlink10.messages.servo_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.servo_position, this.servo_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : Timestamp (uint64_t)
+                pin_id                    : A member of the PinsList enum (uint8_t)
+                last_change_timestamp        : Last change timestamp of pin (uint64_t)
+                changes_counter           : Number of changes of pin (uint8_t)
+                current_state             : Current state of pin (uint8_t)
+
+*/
+    mavlink10.messages.pin_tm = function( ...moreargs ) {
+     [ this.timestamp , this.pin_id , this.last_change_timestamp , this.changes_counter , this.current_state ] = moreargs;
+
+
+    this._format = '<QQBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_PIN_TM;
+    this.order_map = [0, 2, 1, 3, 4];
+    this.len_map = [1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0];
+    this.crc_extra = 255;
+    this._name = 'PIN_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'pin_id', 'last_change_timestamp', 'changes_counter', 'current_state'];
+
+}
+
+mavlink10.messages.pin_tm.prototype = new mavlink10.message;
+mavlink10.messages.pin_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.last_change_timestamp, this.pin_id, this.changes_counter, this.current_state];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : Timestamp (uint64_t)
+                main_radio_present        : Boolean indicating the presence of the main radio (uint8_t)
+                main_packet_tx_error_count        : Number of errors during send (uint16_t)
+                main_tx_bitrate           : Send bitrate (uint16_t)
+                main_packet_rx_success_count        : Number of succesfull received mavlink packets (uint16_t)
+                main_packet_rx_drop_count        : Number of dropped mavlink packets (uint16_t)
+                main_rx_bitrate           : Receive bitrate (uint16_t)
+                main_rx_rssi              : Receive RSSI (float)
+                main_rx_fei               : Receive frequency error index (float)
+                payload_radio_present        : Boolean indicating the presence of the payload radio (uint8_t)
+                payload_packet_tx_error_count        : Number of errors during send (uint16_t)
+                payload_tx_bitrate        : Send bitrate (uint16_t)
+                payload_packet_rx_success_count        : Number of succesfull received mavlink packets (uint16_t)
+                payload_packet_rx_drop_count        : Number of dropped mavlink packets (uint16_t)
+                payload_rx_bitrate        : Receive bitrate (uint16_t)
+                payload_rx_rssi           : Receive RSSI (float)
+                payload_rx_fei            : Receive frequency error index (float)
+                ethernet_present          : Boolean indicating the presence of the ethernet module (uint8_t)
+                ethernet_status           : Status flag indicating the status of the ethernet PHY (uint8_t)
+                battery_voltage           : Battery voltage (float)
+
+*/
+    mavlink10.messages.receiver_tm = function( ...moreargs ) {
+     [ this.timestamp , this.main_radio_present , this.main_packet_tx_error_count , this.main_tx_bitrate , this.main_packet_rx_success_count , this.main_packet_rx_drop_count , this.main_rx_bitrate , this.main_rx_rssi , this.main_rx_fei , this.payload_radio_present , this.payload_packet_tx_error_count , this.payload_tx_bitrate , this.payload_packet_rx_success_count , this.payload_packet_rx_drop_count , this.payload_rx_bitrate , this.payload_rx_rssi , this.payload_rx_fei , this.ethernet_present , this.ethernet_status , this.battery_voltage ] = moreargs;
+
+
+    this._format = '<QfffffHHHHHHHHHHBBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_RECEIVER_TM;
+    this.order_map = [0, 16, 6, 7, 8, 9, 10, 1, 2, 17, 11, 12, 13, 14, 15, 3, 4, 18, 19, 5];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 117;
+    this._name = 'RECEIVER_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'main_rx_fei', 'payload_radio_present', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'payload_rx_rssi', 'payload_rx_fei', 'ethernet_present', 'ethernet_status', 'battery_voltage'];
+
+}
+
+mavlink10.messages.receiver_tm.prototype = new mavlink10.message;
+mavlink10.messages.receiver_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.main_rx_rssi, this.main_rx_fei, this.payload_rx_rssi, this.payload_rx_fei, this.battery_voltage, this.main_packet_tx_error_count, this.main_tx_bitrate, this.main_packet_rx_success_count, this.main_packet_rx_drop_count, this.main_rx_bitrate, this.payload_packet_tx_error_count, this.payload_tx_bitrate, this.payload_packet_rx_success_count, this.payload_packet_rx_drop_count, this.payload_rx_bitrate, this.main_radio_present, this.payload_radio_present, this.ethernet_present, this.ethernet_status];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+
+
+                timestamp                 : Timestamp (uint64_t)
+                yaw                       : Current Yaw (float)
+                pitch                     : Current Pitch (float)
+                roll                      : Current Roll (float)
+                target_yaw                : Target Yaw (float)
+                target_pitch              : Target Pitch (float)
+                stepperX_pos              : StepperX current position wrt the boot position (float)
+                stepperX_delta            : StepperX last actuated delta angle (float)
+                stepperX_speed            : StepperX current speed (float)
+                stepperY_pos              : StepperY current position wrt the boot position (float)
+                stepperY_delta            : StepperY last actuated delta angle (float)
+                stepperY_speed            : StepperY current Speed (float)
+                gps_latitude              : Latitude (float)
+                gps_longitude             : Longitude (float)
+                gps_height                : Altitude (float)
+                gps_fix                   : Wether the GPS has a FIX (uint8_t)
+                main_radio_present        : Boolean indicating the presence of the main radio (uint8_t)
+                main_packet_tx_error_count        : Number of errors during send (uint16_t)
+                main_tx_bitrate           : Send bitrate (uint16_t)
+                main_packet_rx_success_count        : Number of succesfull received mavlink packets (uint16_t)
+                main_packet_rx_drop_count        : Number of dropped mavlink packets (uint16_t)
+                main_rx_bitrate           : Receive bitrate (uint16_t)
+                main_rx_rssi              : Receive RSSI (float)
+                ethernet_present          : Boolean indicating the presence of the ethernet module (uint8_t)
+                ethernet_status           : Status flag indicating the status of the ethernet PHY (uint8_t)
+                battery_voltage           : Battery voltage (float)
+
+*/
+    mavlink10.messages.arp_tm = function( ...moreargs ) {
+     [ this.timestamp , this.yaw , this.pitch , this.roll , this.target_yaw , this.target_pitch , this.stepperX_pos , this.stepperX_delta , this.stepperX_speed , this.stepperY_pos , this.stepperY_delta , this.stepperY_speed , this.gps_latitude , this.gps_longitude , this.gps_height , this.gps_fix , this.main_radio_present , this.main_packet_tx_error_count , this.main_tx_bitrate , this.main_packet_rx_success_count , this.main_packet_rx_drop_count , this.main_rx_bitrate , this.main_rx_rssi , this.ethernet_present , this.ethernet_status , this.battery_voltage ] = moreargs;
+
+
+    this._format = '<QffffffffffffffffHHHHHBBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_ARP_TM;
+    this.order_map = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 22, 23, 17, 18, 19, 20, 21, 15, 24, 25, 16];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 2;
+    this._name = 'ARP_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'ethernet_present', 'ethernet_status', 'battery_voltage'];
+
+}
+
+mavlink10.messages.arp_tm.prototype = new mavlink10.message;
+mavlink10.messages.arp_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.yaw, this.pitch, this.roll, this.target_yaw, this.target_pitch, this.stepperX_pos, this.stepperX_delta, this.stepperX_speed, this.stepperY_pos, this.stepperY_delta, this.stepperY_speed, this.gps_latitude, this.gps_longitude, this.gps_height, this.main_rx_rssi, this.battery_voltage, this.main_packet_tx_error_count, this.main_tx_bitrate, this.main_packet_rx_success_count, this.main_packet_rx_drop_count, this.main_rx_bitrate, this.gps_fix, this.main_radio_present, this.ethernet_present, this.ethernet_status];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets current antennas coordinates
+
+                latitude                  : Latitude (float)
+                longitude                 : Longitude (float)
+
+*/
+    mavlink10.messages.set_antenna_coordinates_arp_tc = function( ...moreargs ) {
+     [ this.latitude , this.longitude ] = moreargs;
+
+
+    this._format = '<ff';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC;
+    this.order_map = [0, 1];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 202;
+    this._name = 'SET_ANTENNA_COORDINATES_ARP_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['latitude', 'longitude'];
+
+}
+
+mavlink10.messages.set_antenna_coordinates_arp_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_antenna_coordinates_arp_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.latitude, this.longitude];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Sets current rocket coordinates
+
+                latitude                  : Latitude (float)
+                longitude                 : Longitude (float)
+
+*/
+    mavlink10.messages.set_rocket_coordinates_arp_tc = function( ...moreargs ) {
+     [ this.latitude , this.longitude ] = moreargs;
+
+
+    this._format = '<ff';
+    this._id = mavlink10.MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC;
+    this.order_map = [0, 1];
+    this.len_map = [1, 1];
+    this.array_len_map = [0, 0];
+    this.crc_extra = 164;
+    this._name = 'SET_ROCKET_COORDINATES_ARP_TC';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['latitude', 'longitude'];
+
+}
+
+mavlink10.messages.set_rocket_coordinates_arp_tc.prototype = new mavlink10.message;
+mavlink10.messages.set_rocket_coordinates_arp_tc.prototype.pack = function(mav) {
+    var orderedfields = [ this.latitude, this.longitude];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+System status telemetry
+
+                timestamp                 : Timestamp (uint64_t)
+                logger                    : True if the logger started correctly (uint8_t)
+                event_broker              : True if the event broker started correctly (uint8_t)
+                radio                     : True if the radio started correctly (uint8_t)
+                pin_observer              : True if the pin observer started correctly (uint8_t)
+                sensors                   : True if the sensors started correctly (uint8_t)
+                board_scheduler           : True if the board scheduler is running (uint8_t)
+
+*/
+    mavlink10.messages.sys_tm = function( ...moreargs ) {
+     [ this.timestamp , this.logger , this.event_broker , this.radio , this.pin_observer , this.sensors , this.board_scheduler ] = moreargs;
+
+
+    this._format = '<QBBBBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_SYS_TM;
+    this.order_map = [0, 1, 2, 3, 4, 5, 6];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 183;
+    this._name = 'SYS_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'pin_observer', 'sensors', 'board_scheduler'];
+
+}
+
+mavlink10.messages.sys_tm.prototype = new mavlink10.message;
+mavlink10.messages.sys_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.logger, this.event_broker, this.radio, this.pin_observer, this.sensors, this.board_scheduler];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Flight State Machine status telemetry
+
+                timestamp                 : Timestamp (uint64_t)
+                ada_state                 : Apogee Detection Algorithm state (uint8_t)
+                abk_state                 : Air Brakes state (uint8_t)
+                dpl_state                 : Deployment state (uint8_t)
+                fmm_state                 : Flight Mode Manager state (uint8_t)
+                nas_state                 : Navigation and Attitude System state (uint8_t)
+                wes_state                 : Wind Estimation System state (uint8_t)
+
+*/
+    mavlink10.messages.fsm_tm = function( ...moreargs ) {
+     [ this.timestamp , this.ada_state , this.abk_state , this.dpl_state , this.fmm_state , this.nas_state , this.wes_state ] = moreargs;
+
+
+    this._format = '<QBBBBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_FSM_TM;
+    this.order_map = [0, 1, 2, 3, 4, 5, 6];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 242;
+    this._name = 'FSM_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'ada_state', 'abk_state', 'dpl_state', 'fmm_state', 'nas_state', 'wes_state'];
+
+}
+
+mavlink10.messages.fsm_tm.prototype = new mavlink10.message;
+mavlink10.messages.fsm_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.ada_state, this.abk_state, this.dpl_state, this.fmm_state, this.nas_state, this.wes_state];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Logger status telemetry
+
+                timestamp                 : Timestamp (uint64_t)
+                log_number                : Currently active log file, -1 if the logger is inactive (int16_t)
+                too_large_samples         : Number of dropped samples because too large (int32_t)
+                dropped_samples           : Number of dropped samples due to fifo full (int32_t)
+                queued_samples            : Number of samples written to buffer (int32_t)
+                buffers_filled            : Number of buffers filled (int32_t)
+                buffers_written           : Number of buffers written to disk (int32_t)
+                writes_failed             : Number of fwrite() that failed (int32_t)
+                last_write_error          : Error of the last fwrite() that failed (int32_t)
+                average_write_time        : Average time to perform an fwrite() of a buffer (int32_t)
+                max_write_time            : Max time to perform an fwrite() of a buffer (int32_t)
+
+*/
+    mavlink10.messages.logger_tm = function( ...moreargs ) {
+     [ this.timestamp , this.log_number , this.too_large_samples , this.dropped_samples , this.queued_samples , this.buffers_filled , this.buffers_written , this.writes_failed , this.last_write_error , this.average_write_time , this.max_write_time ] = moreargs;
+
+
+    this._format = '<Qiiiiiiiiih';
+    this._id = mavlink10.MAVLINK_MSG_ID_LOGGER_TM;
+    this.order_map = [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 142;
+    this._name = 'LOGGER_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'log_number', 'too_large_samples', 'dropped_samples', 'queued_samples', 'buffers_filled', 'buffers_written', 'writes_failed', 'last_write_error', 'average_write_time', 'max_write_time'];
+
+}
+
+mavlink10.messages.logger_tm.prototype = new mavlink10.message;
+mavlink10.messages.logger_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.too_large_samples, this.dropped_samples, this.queued_samples, this.buffers_filled, this.buffers_written, this.writes_failed, this.last_write_error, this.average_write_time, this.max_write_time, this.log_number];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Status of the TMTCManager telemetry
+
+                timestamp                 : When was this logged (uint64_t)
+                n_send_queue              : Current len of the occupied portion of the queue (uint16_t)
+                max_send_queue            : Max occupied len of the queue (uint16_t)
+                n_send_errors             : Number of packet not sent correctly by the TMTC (uint16_t)
+                msg_received              : Number of received messages (uint8_t)
+                buffer_overrun            : Number of buffer overruns (uint8_t)
+                parse_error               : Number of parse errors (uint8_t)
+                parse_state               : Parsing state machine (uint32_t)
+                packet_idx                : Index in current packet (uint8_t)
+                current_rx_seq            : Sequence number of last packet received (uint8_t)
+                current_tx_seq            : Sequence number of last packet sent (uint8_t)
+                packet_rx_success_count        : Received packets (uint16_t)
+                packet_rx_drop_count        : Number of packet drops (uint16_t)
+
+*/
+    mavlink10.messages.mavlink_stats_tm = function( ...moreargs ) {
+     [ this.timestamp , this.n_send_queue , this.max_send_queue , this.n_send_errors , this.msg_received , this.buffer_overrun , this.parse_error , this.parse_state , this.packet_idx , this.current_rx_seq , this.current_tx_seq , this.packet_rx_success_count , this.packet_rx_drop_count ] = moreargs;
+
+
+    this._format = '<QIHHHHHBBBBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_MAVLINK_STATS_TM;
+    this.order_map = [0, 2, 3, 4, 7, 8, 9, 1, 10, 11, 12, 5, 6];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 108;
+    this._name = 'MAVLINK_STATS_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'n_send_queue', 'max_send_queue', 'n_send_errors', 'msg_received', 'buffer_overrun', 'parse_error', 'parse_state', 'packet_idx', 'current_rx_seq', 'current_tx_seq', 'packet_rx_success_count', 'packet_rx_drop_count'];
+
+}
+
+mavlink10.messages.mavlink_stats_tm.prototype = new mavlink10.message;
+mavlink10.messages.mavlink_stats_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.parse_state, this.n_send_queue, this.max_send_queue, this.n_send_errors, this.packet_rx_success_count, this.packet_rx_drop_count, this.msg_received, this.buffer_overrun, this.parse_error, this.packet_idx, this.current_rx_seq, this.current_tx_seq];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Statistics of the Task Scheduler
+
+                timestamp                 : When was this logged (uint64_t)
+                task_id                   : Task ID (uint8_t)
+                task_period               : Period of the task (uint16_t)
+                task_min                  : Task min period (float)
+                task_max                  : Task max period (float)
+                task_mean                 : Task mean period (float)
+                task_stddev               : Task period std deviation (float)
+
+*/
+    mavlink10.messages.task_stats_tm = function( ...moreargs ) {
+     [ this.timestamp , this.task_id , this.task_period , this.task_min , this.task_max , this.task_mean , this.task_stddev ] = moreargs;
+
+
+    this._format = '<QffffHB';
+    this._id = mavlink10.MAVLINK_MSG_ID_TASK_STATS_TM;
+    this.order_map = [0, 6, 5, 1, 2, 3, 4];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 133;
+    this._name = 'TASK_STATS_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'task_id', 'task_period', 'task_min', 'task_max', 'task_mean', 'task_stddev'];
+
+}
+
+mavlink10.messages.task_stats_tm.prototype = new mavlink10.message;
+mavlink10.messages.task_stats_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.task_min, this.task_max, this.task_mean, this.task_stddev, this.task_period, this.task_id];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Apogee Detection Algorithm status telemetry
+
+                timestamp                 : When was this logged (uint64_t)
+                state                     : ADA current state (uint8_t)
+                kalman_x0                 : Kalman state variable 0 (pressure) (float)
+                kalman_x1                 : Kalman state variable 1 (pressure velocity) (float)
+                kalman_x2                 : Kalman state variable 2 (pressure acceleration) (float)
+                vertical_speed            : Vertical speed computed by the ADA (float)
+                msl_altitude              : Altitude w.r.t. mean sea level (float)
+                ref_pressure              : Calibration pressure (float)
+                ref_altitude              : Calibration altitude (float)
+                ref_temperature           : Calibration temperature (float)
+                msl_pressure              : Expected pressure at mean sea level (float)
+                msl_temperature           : Expected temperature at mean sea level (float)
+                dpl_altitude              : Main parachute deployment altituyde (float)
+
+*/
+    mavlink10.messages.ada_tm = function( ...moreargs ) {
+     [ this.timestamp , this.state , this.kalman_x0 , this.kalman_x1 , this.kalman_x2 , this.vertical_speed , this.msl_altitude , this.ref_pressure , this.ref_altitude , this.ref_temperature , this.msl_pressure , this.msl_temperature , this.dpl_altitude ] = moreargs;
+
+
+    this._format = '<QfffffffffffB';
+    this._id = mavlink10.MAVLINK_MSG_ID_ADA_TM;
+    this.order_map = [0, 12, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 234;
+    this._name = 'ADA_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'state', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'vertical_speed', 'msl_altitude', 'ref_pressure', 'ref_altitude', 'ref_temperature', 'msl_pressure', 'msl_temperature', 'dpl_altitude'];
+
+}
+
+mavlink10.messages.ada_tm.prototype = new mavlink10.message;
+mavlink10.messages.ada_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.kalman_x0, this.kalman_x1, this.kalman_x2, this.vertical_speed, this.msl_altitude, this.ref_pressure, this.ref_altitude, this.ref_temperature, this.msl_pressure, this.msl_temperature, this.dpl_altitude, this.state];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Navigation System status telemetry
+
+                timestamp                 : When was this logged (uint64_t)
+                state                     : NAS current state (uint8_t)
+                nas_n                     : Navigation system estimated noth position (float)
+                nas_e                     : Navigation system estimated east position (float)
+                nas_d                     : Navigation system estimated down position (float)
+                nas_vn                    : Navigation system estimated north velocity (float)
+                nas_ve                    : Navigation system estimated east velocity (float)
+                nas_vd                    : Navigation system estimated down velocity (float)
+                nas_qx                    : Navigation system estimated attitude (qx) (float)
+                nas_qy                    : Navigation system estimated attitude (qy) (float)
+                nas_qz                    : Navigation system estimated attitude (qz) (float)
+                nas_qw                    : Navigation system estimated attitude (qw) (float)
+                nas_bias_x                : Navigation system gyroscope bias on x axis (float)
+                nas_bias_y                : Navigation system gyroscope bias on y axis (float)
+                nas_bias_z                : Navigation system gyroscope bias on z axis (float)
+                ref_pressure              : Calibration pressure (float)
+                ref_temperature           : Calibration temperature (float)
+                ref_latitude              : Calibration latitude (float)
+                ref_longitude             : Calibration longitude (float)
+
+*/
+    mavlink10.messages.nas_tm = function( ...moreargs ) {
+     [ this.timestamp , this.state , this.nas_n , this.nas_e , this.nas_d , this.nas_vn , this.nas_ve , this.nas_vd , this.nas_qx , this.nas_qy , this.nas_qz , this.nas_qw , this.nas_bias_x , this.nas_bias_y , this.nas_bias_z , this.ref_pressure , this.ref_temperature , this.ref_latitude , this.ref_longitude ] = moreargs;
+
+
+    this._format = '<QfffffffffffffffffB';
+    this._id = mavlink10.MAVLINK_MSG_ID_NAS_TM;
+    this.order_map = [0, 18, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 66;
+    this._name = 'NAS_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'state', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'ref_pressure', 'ref_temperature', 'ref_latitude', 'ref_longitude'];
+
+}
+
+mavlink10.messages.nas_tm.prototype = new mavlink10.message;
+mavlink10.messages.nas_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.nas_n, this.nas_e, this.nas_d, this.nas_vn, this.nas_ve, this.nas_vd, this.nas_qx, this.nas_qy, this.nas_qz, this.nas_qw, this.nas_bias_x, this.nas_bias_y, this.nas_bias_z, this.ref_pressure, this.ref_temperature, this.ref_latitude, this.ref_longitude, this.state];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Mass Estimation Algorithm status telemetry
+
+                timestamp                 : When was this logged (uint64_t)
+                state                     : MEA current state (uint8_t)
+                kalman_x0                 : Kalman state variable 0 (corrected pressure) (float)
+                kalman_x1                 : Kalman state variable 1 (float)
+                kalman_x2                 : Kalman state variable 2 (mass) (float)
+                mass                      : Mass estimated (float)
+                corrected_pressure        : Corrected pressure (float)
+
+*/
+    mavlink10.messages.mea_tm = function( ...moreargs ) {
+     [ this.timestamp , this.state , this.kalman_x0 , this.kalman_x1 , this.kalman_x2 , this.mass , this.corrected_pressure ] = moreargs;
+
+
+    this._format = '<QfffffB';
+    this._id = mavlink10.MAVLINK_MSG_ID_MEA_TM;
+    this.order_map = [0, 6, 1, 2, 3, 4, 5];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 11;
+    this._name = 'MEA_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'state', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'mass', 'corrected_pressure'];
+
+}
+
+mavlink10.messages.mea_tm.prototype = new mavlink10.message;
+mavlink10.messages.mea_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.kalman_x0, this.kalman_x1, this.kalman_x2, this.mass, this.corrected_pressure, this.state];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+High Rate Telemetry
+
+                timestamp                 : Timestamp in microseconds (uint64_t)
+                ada_state                 : ADA Controller State (uint8_t)
+                fmm_state                 : Flight Mode Manager State (uint8_t)
+                dpl_state                 : Deployment Controller State (uint8_t)
+                abk_state                 : Airbrake FSM state (uint8_t)
+                nas_state                 : Navigation System FSM State (uint8_t)
+                mea_state                 : MEA Controller State (uint8_t)
+                pressure_ada              : Atmospheric pressure estimated by ADA (float)
+                pressure_digi             : Pressure from digital sensor (float)
+                pressure_static           : Pressure from static port (float)
+                pressure_dpl              : Pressure from deployment vane sensor (float)
+                airspeed_pitot            : Pitot airspeed (float)
+                altitude_agl              : Altitude above ground level (float)
+                ada_vert_speed            : Vertical speed estimated by ADA (float)
+                mea_mass                  : Mass estimated by MEA (float)
+                acc_x                     : Acceleration on X axis (body) (float)
+                acc_y                     : Acceleration on Y axis (body) (float)
+                acc_z                     : Acceleration on Z axis (body) (float)
+                gyro_x                    : Angular speed on X axis (body) (float)
+                gyro_y                    : Angular speed on Y axis (body) (float)
+                gyro_z                    : Angular speed on Z axis (body) (float)
+                mag_x                     : Magnetic field on X axis (body) (float)
+                mag_y                     : Magnetic field on Y axis (body) (float)
+                mag_z                     : Magnetic field on Z axis (body) (float)
+                gps_fix                   : GPS fix (1 = fix, 0 = no fix) (uint8_t)
+                gps_lat                   : Latitude (float)
+                gps_lon                   : Longitude (float)
+                gps_alt                   : GPS Altitude (float)
+                abk_angle                 : Air Brakes angle (float)
+                nas_n                     : Navigation system estimated noth position (float)
+                nas_e                     : Navigation system estimated east position (float)
+                nas_d                     : Navigation system estimated down position (float)
+                nas_vn                    : Navigation system estimated north velocity (float)
+                nas_ve                    : Navigation system estimated east velocity (float)
+                nas_vd                    : Navigation system estimated down velocity (float)
+                nas_qx                    : Navigation system estimated attitude (qx) (float)
+                nas_qy                    : Navigation system estimated attitude (qy) (float)
+                nas_qz                    : Navigation system estimated attitude (qz) (float)
+                nas_qw                    : Navigation system estimated attitude (qw) (float)
+                nas_bias_x                : Navigation system gyroscope bias on x axis (float)
+                nas_bias_y                : Navigation system gyroscope bias on y axis (float)
+                nas_bias_z                : Navigation system gyroscope bias on z axis (float)
+                pin_quick_connector        : Quick connector detach pin (float)
+                pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (uint8_t)
+                pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (uint8_t)
+                pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (uint8_t)
+                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (uint8_t)
+                battery_voltage           : Battery voltage (float)
+                cam_battery_voltage        : Camera battery voltage (float)
+                current_consumption        : Battery current (float)
+                temperature               : Temperature (float)
+                logger_error              : Logger error (0 = no error, -1 otherwise) (int8_t)
+
+*/
+    mavlink10.messages.rocket_flight_tm = function( ...moreargs ) {
+     [ this.timestamp , this.ada_state , this.fmm_state , this.dpl_state , this.abk_state , this.nas_state , this.mea_state , this.pressure_ada , this.pressure_digi , this.pressure_static , this.pressure_dpl , this.airspeed_pitot , this.altitude_agl , this.ada_vert_speed , this.mea_mass , this.acc_x , this.acc_y , this.acc_z , this.gyro_x , this.gyro_y , this.gyro_z , this.mag_x , this.mag_y , this.mag_z , this.gps_fix , this.gps_lat , this.gps_lon , this.gps_alt , this.abk_angle , this.nas_n , this.nas_e , this.nas_d , this.nas_vn , this.nas_ve , this.nas_vd , this.nas_qx , this.nas_qy , this.nas_qz , this.nas_qw , this.nas_bias_x , this.nas_bias_y , this.nas_bias_z , this.pin_quick_connector , this.pin_launch , this.pin_nosecone , this.pin_expulsion , this.cutter_presence , this.battery_voltage , this.cam_battery_voltage , this.current_consumption , this.temperature , this.logger_error ] = moreargs;
+
+
+    this._format = '<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb';
+    this._id = mavlink10.MAVLINK_MSG_ID_ROCKET_FLIGHT_TM;
+    this.order_map = [0, 40, 41, 42, 43, 44, 45, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 46, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 47, 48, 49, 50, 36, 37, 38, 39, 51];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 214;
+    this._name = 'ROCKET_FLIGHT_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_quick_connector', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'logger_error'];
+
+}
+
+mavlink10.messages.rocket_flight_tm.prototype = new mavlink10.message;
+mavlink10.messages.rocket_flight_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.pressure_ada, this.pressure_digi, this.pressure_static, this.pressure_dpl, this.airspeed_pitot, this.altitude_agl, this.ada_vert_speed, this.mea_mass, this.acc_x, this.acc_y, this.acc_z, this.gyro_x, this.gyro_y, this.gyro_z, this.mag_x, this.mag_y, this.mag_z, this.gps_lat, this.gps_lon, this.gps_alt, this.abk_angle, this.nas_n, this.nas_e, this.nas_d, this.nas_vn, this.nas_ve, this.nas_vd, this.nas_qx, this.nas_qy, this.nas_qz, this.nas_qw, this.nas_bias_x, this.nas_bias_y, this.nas_bias_z, this.pin_quick_connector, this.battery_voltage, this.cam_battery_voltage, this.current_consumption, this.temperature, this.ada_state, this.fmm_state, this.dpl_state, this.abk_state, this.nas_state, this.mea_state, this.gps_fix, this.pin_launch, this.pin_nosecone, this.pin_expulsion, this.cutter_presence, this.logger_error];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+High Rate Telemetry
+
+                timestamp                 : Timestamp in microseconds (uint64_t)
+                fmm_state                 : Flight Mode Manager State (uint8_t)
+                nas_state                 : Navigation System FSM State (uint8_t)
+                wes_state                 : Wind Estimation System FSM State (uint8_t)
+                pressure_digi             : Pressure from digital sensor (float)
+                pressure_static           : Pressure from static port (float)
+                airspeed_pitot            : Pitot airspeed (float)
+                altitude_agl              : Altitude above ground level (float)
+                acc_x                     : Acceleration on X axis (body) (float)
+                acc_y                     : Acceleration on Y axis (body) (float)
+                acc_z                     : Acceleration on Z axis (body) (float)
+                gyro_x                    : Angular speed on X axis (body) (float)
+                gyro_y                    : Angular speed on Y axis (body) (float)
+                gyro_z                    : Angular speed on Z axis (body) (float)
+                mag_x                     : Magnetic field on X axis (body) (float)
+                mag_y                     : Magnetic field on Y axis (body) (float)
+                mag_z                     : Magnetic field on Z axis (body) (float)
+                gps_fix                   : GPS fix (1 = fix, 0 = no fix) (uint8_t)
+                gps_lat                   : Latitude (float)
+                gps_lon                   : Longitude (float)
+                gps_alt                   : GPS Altitude (float)
+                left_servo_angle          : Left servo motor angle (float)
+                right_servo_angle         : Right servo motor angle (float)
+                nas_n                     : Navigation system estimated noth position (float)
+                nas_e                     : Navigation system estimated east position (float)
+                nas_d                     : Navigation system estimated down position (float)
+                nas_vn                    : Navigation system estimated north velocity (float)
+                nas_ve                    : Navigation system estimated east velocity (float)
+                nas_vd                    : Navigation system estimated down velocity (float)
+                nas_qx                    : Navigation system estimated attitude (qx) (float)
+                nas_qy                    : Navigation system estimated attitude (qy) (float)
+                nas_qz                    : Navigation system estimated attitude (qz) (float)
+                nas_qw                    : Navigation system estimated attitude (qw) (float)
+                nas_bias_x                : Navigation system gyroscope bias on x axis (float)
+                nas_bias_y                : Navigation system gyroscope bias on y axis (float)
+                nas_bias_z                : Navigation system gyroscope bias on z axis (float)
+                wes_n                     : Wind estimated north velocity (float)
+                wes_e                     : Wind estimated east velocity (float)
+                pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (uint8_t)
+                battery_voltage           : Battery voltage (float)
+                cam_battery_voltage        : Camera battery voltage (float)
+                current_consumption        : Battery current (float)
+                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (uint8_t)
+                temperature               : Temperature (float)
+                logger_error              : Logger error (0 = no error) (int8_t)
+
+*/
+    mavlink10.messages.payload_flight_tm = function( ...moreargs ) {
+     [ this.timestamp , this.fmm_state , this.nas_state , this.wes_state , this.pressure_digi , this.pressure_static , this.airspeed_pitot , this.altitude_agl , this.acc_x , this.acc_y , this.acc_z , this.gyro_x , this.gyro_y , this.gyro_z , this.mag_x , this.mag_y , this.mag_z , this.gps_fix , this.gps_lat , this.gps_lon , this.gps_alt , this.left_servo_angle , this.right_servo_angle , this.nas_n , this.nas_e , this.nas_d , this.nas_vn , this.nas_ve , this.nas_vd , this.nas_qx , this.nas_qy , this.nas_qz , this.nas_qw , this.nas_bias_x , this.nas_bias_y , this.nas_bias_z , this.wes_n , this.wes_e , this.pin_nosecone , this.battery_voltage , this.cam_battery_voltage , this.current_consumption , this.cutter_presence , this.temperature , this.logger_error ] = moreargs;
+
+
+    this._format = '<QfffffffffffffffffffffffffffffffffffffBBBBBBb';
+    this._id = mavlink10.MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM;
+    this.order_map = [0, 38, 39, 40, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 41, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 42, 34, 35, 36, 43, 37, 44];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 84;
+    this._name = 'PAYLOAD_FLIGHT_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'fmm_state', 'nas_state', 'wes_state', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'pin_nosecone', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'cutter_presence', 'temperature', 'logger_error'];
+
+}
+
+mavlink10.messages.payload_flight_tm.prototype = new mavlink10.message;
+mavlink10.messages.payload_flight_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.pressure_digi, this.pressure_static, this.airspeed_pitot, this.altitude_agl, this.acc_x, this.acc_y, this.acc_z, this.gyro_x, this.gyro_y, this.gyro_z, this.mag_x, this.mag_y, this.mag_z, this.gps_lat, this.gps_lon, this.gps_alt, this.left_servo_angle, this.right_servo_angle, this.nas_n, this.nas_e, this.nas_d, this.nas_vn, this.nas_ve, this.nas_vd, this.nas_qx, this.nas_qy, this.nas_qz, this.nas_qw, this.nas_bias_x, this.nas_bias_y, this.nas_bias_z, this.wes_n, this.wes_e, this.battery_voltage, this.cam_battery_voltage, this.current_consumption, this.temperature, this.fmm_state, this.nas_state, this.wes_state, this.gps_fix, this.pin_nosecone, this.cutter_presence, this.logger_error];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Low Rate Telemetry
+
+                liftoff_ts                : System clock at liftoff (uint64_t)
+                liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration (uint64_t)
+                liftoff_max_acc           : Maximum liftoff acceleration (float)
+                dpl_ts                    : System clock at drouge deployment (uint64_t)
+                dpl_max_acc               : Max acceleration during drouge deployment (float)
+                max_z_speed_ts            : System clock at ADA max vertical speed (uint64_t)
+                max_z_speed               : Max measured vertical speed - ADA (float)
+                max_airspeed_pitot        : Max speed read by the pitot tube (float)
+                max_speed_altitude        : Altitude at max speed (float)
+                apogee_ts                 : System clock at apogee (uint64_t)
+                apogee_lat                : Apogee latitude (float)
+                apogee_lon                : Apogee longitude (float)
+                apogee_alt                : Apogee altitude (float)
+                min_pressure              : Apogee pressure - Digital barometer (float)
+                ada_min_pressure          : Apogee pressure - ADA filtered (float)
+                dpl_vane_max_pressure        : Max pressure in the deployment bay during drogue deployment (float)
+                cpu_load                  : CPU load in percentage (float)
+                free_heap                 : Amount of available heap in memory (uint32_t)
+
+*/
+    mavlink10.messages.rocket_stats_tm = function( ...moreargs ) {
+     [ this.liftoff_ts , this.liftoff_max_acc_ts , this.liftoff_max_acc , this.dpl_ts , this.dpl_max_acc , this.max_z_speed_ts , this.max_z_speed , this.max_airspeed_pitot , this.max_speed_altitude , this.apogee_ts , this.apogee_lat , this.apogee_lon , this.apogee_alt , this.min_pressure , this.ada_min_pressure , this.dpl_vane_max_pressure , this.cpu_load , this.free_heap ] = moreargs;
+
+
+    this._format = '<QQQQQffffffffffffI';
+    this._id = mavlink10.MAVLINK_MSG_ID_ROCKET_STATS_TM;
+    this.order_map = [0, 1, 5, 2, 6, 3, 7, 8, 9, 4, 10, 11, 12, 13, 14, 15, 16, 17];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 245;
+    this._name = 'ROCKET_STATS_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_vane_max_pressure', 'cpu_load', 'free_heap'];
+
+}
+
+mavlink10.messages.rocket_stats_tm.prototype = new mavlink10.message;
+mavlink10.messages.rocket_stats_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.liftoff_ts, this.liftoff_max_acc_ts, this.dpl_ts, this.max_z_speed_ts, this.apogee_ts, this.liftoff_max_acc, this.dpl_max_acc, this.max_z_speed, this.max_airspeed_pitot, this.max_speed_altitude, this.apogee_lat, this.apogee_lon, this.apogee_alt, this.min_pressure, this.ada_min_pressure, this.dpl_vane_max_pressure, this.cpu_load, this.free_heap];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Low Rate Telemetry
+
+                liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration (uint64_t)
+                liftoff_max_acc           : Maximum liftoff acceleration (float)
+                dpl_ts                    : System clock at drouge deployment (uint64_t)
+                dpl_max_acc               : Max acceleration during drouge deployment (float)
+                max_z_speed_ts            : System clock at max vertical speed (uint64_t)
+                max_z_speed               : Max measured vertical speed (float)
+                max_airspeed_pitot        : Max speed read by the pitot tube (float)
+                max_speed_altitude        : Altitude at max speed (float)
+                apogee_ts                 : System clock at apogee (uint64_t)
+                apogee_lat                : Apogee latitude (float)
+                apogee_lon                : Apogee longitude (float)
+                apogee_alt                : Apogee altitude (float)
+                min_pressure              : Apogee pressure - Digital barometer (float)
+                cpu_load                  : CPU load in percentage (float)
+                free_heap                 : Amount of available heap in memory (uint32_t)
+
+*/
+    mavlink10.messages.payload_stats_tm = function( ...moreargs ) {
+     [ this.liftoff_max_acc_ts , this.liftoff_max_acc , this.dpl_ts , this.dpl_max_acc , this.max_z_speed_ts , this.max_z_speed , this.max_airspeed_pitot , this.max_speed_altitude , this.apogee_ts , this.apogee_lat , this.apogee_lon , this.apogee_alt , this.min_pressure , this.cpu_load , this.free_heap ] = moreargs;
+
+
+    this._format = '<QQQQffffffffffI';
+    this._id = mavlink10.MAVLINK_MSG_ID_PAYLOAD_STATS_TM;
+    this.order_map = [0, 4, 1, 5, 2, 6, 7, 8, 3, 9, 10, 11, 12, 13, 14];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 115;
+    this._name = 'PAYLOAD_STATS_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap'];
+
+}
+
+mavlink10.messages.payload_stats_tm.prototype = new mavlink10.message;
+mavlink10.messages.payload_stats_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.liftoff_max_acc_ts, this.dpl_ts, this.max_z_speed_ts, this.apogee_ts, this.liftoff_max_acc, this.dpl_max_acc, this.max_z_speed, this.max_airspeed_pitot, this.max_speed_altitude, this.apogee_lat, this.apogee_lon, this.apogee_alt, this.min_pressure, this.cpu_load, this.free_heap];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Ground Segment Equipment telemetry
+
+                timestamp                 : Timestamp in microseconds (uint64_t)
+                loadcell_rocket           : Rocket weight (float)
+                loadcell_vessel           : External tank weight (float)
+                filling_pressure          : Refueling line pressure (float)
+                vessel_pressure           : Vessel tank pressure (float)
+                arming_state              : 1 If the rocket is armed (uint8_t)
+                filling_valve_state        : 1 If the filling valve is open (uint8_t)
+                venting_valve_state        : 1 If the venting valve is open (uint8_t)
+                release_valve_state        : 1 If the release valve is open (uint8_t)
+                main_valve_state          : 1 If the main valve is open (uint8_t)
+                ignition_state            : 1 If the RIG is in ignition process (uint8_t)
+                tars_state                : 1 If the TARS algorithm is running (uint8_t)
+                battery_voltage           : Battery voltage (float)
+                current_consumption        : RIG current (float)
+                main_board_status         : MAIN board status [0: not present, 1: online, 2: armed] (uint8_t)
+                payload_board_status        : PAYLOAD board status [0: not present, 1: online, 2: armed] (uint8_t)
+                motor_board_status        : MOTOR board status [0: not present, 1: online, 2: armed] (uint8_t)
+
+*/
+    mavlink10.messages.gse_tm = function( ...moreargs ) {
+     [ this.timestamp , this.loadcell_rocket , this.loadcell_vessel , this.filling_pressure , this.vessel_pressure , this.arming_state , this.filling_valve_state , this.venting_valve_state , this.release_valve_state , this.main_valve_state , this.ignition_state , this.tars_state , this.battery_voltage , this.current_consumption , this.main_board_status , this.payload_board_status , this.motor_board_status ] = moreargs;
+
+
+    this._format = '<QffffffBBBBBBBBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_GSE_TM;
+    this.order_map = [0, 1, 2, 3, 4, 7, 8, 9, 10, 11, 12, 13, 5, 6, 14, 15, 16];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 63;
+    this._name = 'GSE_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'ignition_state', 'tars_state', 'battery_voltage', 'current_consumption', 'main_board_status', 'payload_board_status', 'motor_board_status'];
+
+}
+
+mavlink10.messages.gse_tm.prototype = new mavlink10.message;
+mavlink10.messages.gse_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.loadcell_rocket, this.loadcell_vessel, this.filling_pressure, this.vessel_pressure, this.battery_voltage, this.current_consumption, this.arming_state, this.filling_valve_state, this.venting_valve_state, this.release_valve_state, this.main_valve_state, this.ignition_state, this.tars_state, this.main_board_status, this.payload_board_status, this.motor_board_status];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+/* 
+Motor rocket telemetry
+
+                timestamp                 : Timestamp in microseconds (uint64_t)
+                top_tank_pressure         : Tank upper pressure (float)
+                bottom_tank_pressure        : Tank bottom pressure (float)
+                combustion_chamber_pressure        : Pressure inside the combustion chamber used for automatic shutdown (float)
+                floating_level            : Floating level in tank (uint8_t)
+                tank_temperature          : Tank temperature (float)
+                main_valve_state          : 1 If the main valve is open (uint8_t)
+                venting_valve_state        : 1 If the venting valve is open (uint8_t)
+                battery_voltage           : Battery voltage (float)
+                current_consumption        : Current drained from the battery (float)
+
+*/
+    mavlink10.messages.motor_tm = function( ...moreargs ) {
+     [ this.timestamp , this.top_tank_pressure , this.bottom_tank_pressure , this.combustion_chamber_pressure , this.floating_level , this.tank_temperature , this.main_valve_state , this.venting_valve_state , this.battery_voltage , this.current_consumption ] = moreargs;
+
+
+    this._format = '<QffffffBBB';
+    this._id = mavlink10.MAVLINK_MSG_ID_MOTOR_TM;
+    this.order_map = [0, 1, 2, 3, 7, 4, 8, 9, 5, 6];
+    this.len_map = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1];
+    this.array_len_map = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
+    this.crc_extra = 79;
+    this._name = 'MOTOR_TM';
+
+    this._instance_field = undefined;
+    this._instance_offset = -1;
+
+    this.fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'floating_level', 'tank_temperature', 'main_valve_state', 'venting_valve_state', 'battery_voltage', 'current_consumption'];
+
+}
+
+mavlink10.messages.motor_tm.prototype = new mavlink10.message;
+mavlink10.messages.motor_tm.prototype.pack = function(mav) {
+    var orderedfields = [ this.timestamp, this.top_tank_pressure, this.bottom_tank_pressure, this.combustion_chamber_pressure, this.tank_temperature, this.battery_voltage, this.current_consumption, this.floating_level, this.main_valve_state, this.venting_valve_state];
+    var j = jspack.Pack(this._format, orderedfields);
+    if (j === false ) throw new Error("jspack unable to handle this packet");
+    return mavlink10.message.prototype.pack.call(this, mav, this.crc_extra, j );
+}
+
+
+mavlink10.map = {
+        1: { format: '<Q', type: mavlink10.messages.ping_tc, order_map: [0], crc_extra: 136 },
+        2: { format: '<B', type: mavlink10.messages.command_tc, order_map: [0], crc_extra: 198 },
+        3: { format: '<B', type: mavlink10.messages.system_tm_request_tc, order_map: [0], crc_extra: 165 },
+        4: { format: '<B', type: mavlink10.messages.sensor_tm_request_tc, order_map: [0], crc_extra: 248 },
+        5: { format: '<B', type: mavlink10.messages.servo_tm_request_tc, order_map: [0], crc_extra: 184 },
+        6: { format: '<fB', type: mavlink10.messages.set_servo_angle_tc, order_map: [1, 0], crc_extra: 215 },
+        7: { format: '<B', type: mavlink10.messages.wiggle_servo_tc, order_map: [0], crc_extra: 160 },
+        8: { format: '<B', type: mavlink10.messages.reset_servo_tc, order_map: [0], crc_extra: 226 },
+        9: { format: '<f', type: mavlink10.messages.set_reference_altitude_tc, order_map: [0], crc_extra: 113 },
+        10: { format: '<f', type: mavlink10.messages.set_reference_temperature_tc, order_map: [0], crc_extra: 38 },
+        11: { format: '<fff', type: mavlink10.messages.set_orientation_tc, order_map: [0, 1, 2], crc_extra: 71 },
+        12: { format: '<ff', type: mavlink10.messages.set_coordinates_tc, order_map: [0, 1], crc_extra: 67 },
+        13: { format: '<BB', type: mavlink10.messages.raw_event_tc, order_map: [0, 1], crc_extra: 218 },
+        14: { format: '<f', type: mavlink10.messages.set_deployment_altitude_tc, order_map: [0], crc_extra: 44 },
+        15: { format: '<ff', type: mavlink10.messages.set_target_coordinates_tc, order_map: [0, 1], crc_extra: 81 },
+        16: { format: '<B', type: mavlink10.messages.set_algorithm_tc, order_map: [0], crc_extra: 181 },
+        17: { format: '<IB', type: mavlink10.messages.set_atomic_valve_timing_tc, order_map: [1, 0], crc_extra: 110 },
+        18: { format: '<fB', type: mavlink10.messages.set_valve_maximum_aperture_tc, order_map: [1, 0], crc_extra: 22 },
+        19: { format: '<BBBBBBB', type: mavlink10.messages.conrig_state_tc, order_map: [0, 1, 2, 3, 4, 5, 6], crc_extra: 65 },
+        20: { format: '<I', type: mavlink10.messages.set_ignition_time_tc, order_map: [0], crc_extra: 79 },
+        21: { format: '<fB', type: mavlink10.messages.set_stepper_angle_tc, order_map: [1, 0], crc_extra: 180 },
+        22: { format: '<fB', type: mavlink10.messages.set_stepper_steps_tc, order_map: [1, 0], crc_extra: 246 },
+        100: { format: '<BB', type: mavlink10.messages.ack_tm, order_map: [0, 1], crc_extra: 50 },
+        101: { format: '<BB', type: mavlink10.messages.nack_tm, order_map: [0, 1], crc_extra: 146 },
+        102: { format: '<Qdddfffff20sBB', type: mavlink10.messages.gps_tm, order_map: [0, 9, 10, 1, 2, 3, 4, 5, 6, 7, 8, 11], crc_extra: 57 },
+        103: { format: '<Qfffffffff20s', type: mavlink10.messages.imu_tm, order_map: [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9], crc_extra: 72 },
+        104: { format: '<Qf20s', type: mavlink10.messages.pressure_tm, order_map: [0, 2, 1], crc_extra: 87 },
+        105: { format: '<Qffffffff20s', type: mavlink10.messages.adc_tm, order_map: [0, 9, 1, 2, 3, 4, 5, 6, 7, 8], crc_extra: 229 },
+        106: { format: '<Qf20s', type: mavlink10.messages.voltage_tm, order_map: [0, 2, 1], crc_extra: 245 },
+        107: { format: '<Qf20s', type: mavlink10.messages.current_tm, order_map: [0, 2, 1], crc_extra: 212 },
+        108: { format: '<Qf20s', type: mavlink10.messages.temp_tm, order_map: [0, 2, 1], crc_extra: 140 },
+        109: { format: '<Qf20s', type: mavlink10.messages.load_tm, order_map: [0, 2, 1], crc_extra: 148 },
+        110: { format: '<Qfffffff20s', type: mavlink10.messages.attitude_tm, order_map: [0, 8, 1, 2, 3, 4, 5, 6, 7], crc_extra: 6 },
+        111: { format: '<20sB', type: mavlink10.messages.sensor_state_tm, order_map: [0, 1], crc_extra: 155 },
+        112: { format: '<fB', type: mavlink10.messages.servo_tm, order_map: [1, 0], crc_extra: 87 },
+        113: { format: '<QQBBB', type: mavlink10.messages.pin_tm, order_map: [0, 2, 1, 3, 4], crc_extra: 255 },
+        150: { format: '<QfffffHHHHHHHHHHBBBB', type: mavlink10.messages.receiver_tm, order_map: [0, 16, 6, 7, 8, 9, 10, 1, 2, 17, 11, 12, 13, 14, 15, 3, 4, 18, 19, 5], crc_extra: 117 },
+        169: { format: '<QffffffffffffffffHHHHHBBBB', type: mavlink10.messages.arp_tm, order_map: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 22, 23, 17, 18, 19, 20, 21, 15, 24, 25, 16], crc_extra: 2 },
+        170: { format: '<ff', type: mavlink10.messages.set_antenna_coordinates_arp_tc, order_map: [0, 1], crc_extra: 202 },
+        171: { format: '<ff', type: mavlink10.messages.set_rocket_coordinates_arp_tc, order_map: [0, 1], crc_extra: 164 },
+        200: { format: '<QBBBBBB', type: mavlink10.messages.sys_tm, order_map: [0, 1, 2, 3, 4, 5, 6], crc_extra: 183 },
+        201: { format: '<QBBBBBB', type: mavlink10.messages.fsm_tm, order_map: [0, 1, 2, 3, 4, 5, 6], crc_extra: 242 },
+        202: { format: '<Qiiiiiiiiih', type: mavlink10.messages.logger_tm, order_map: [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9], crc_extra: 142 },
+        203: { format: '<QIHHHHHBBBBBB', type: mavlink10.messages.mavlink_stats_tm, order_map: [0, 2, 3, 4, 7, 8, 9, 1, 10, 11, 12, 5, 6], crc_extra: 108 },
+        204: { format: '<QffffHB', type: mavlink10.messages.task_stats_tm, order_map: [0, 6, 5, 1, 2, 3, 4], crc_extra: 133 },
+        205: { format: '<QfffffffffffB', type: mavlink10.messages.ada_tm, order_map: [0, 12, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11], crc_extra: 234 },
+        206: { format: '<QfffffffffffffffffB', type: mavlink10.messages.nas_tm, order_map: [0, 18, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17], crc_extra: 66 },
+        207: { format: '<QfffffB', type: mavlink10.messages.mea_tm, order_map: [0, 6, 1, 2, 3, 4, 5], crc_extra: 11 },
+        208: { format: '<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', type: mavlink10.messages.rocket_flight_tm, order_map: [0, 40, 41, 42, 43, 44, 45, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 46, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 47, 48, 49, 50, 36, 37, 38, 39, 51], crc_extra: 214 },
+        209: { format: '<QfffffffffffffffffffffffffffffffffffffBBBBBBb', type: mavlink10.messages.payload_flight_tm, order_map: [0, 38, 39, 40, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 41, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 42, 34, 35, 36, 43, 37, 44], crc_extra: 84 },
+        210: { format: '<QQQQQffffffffffffI', type: mavlink10.messages.rocket_stats_tm, order_map: [0, 1, 5, 2, 6, 3, 7, 8, 9, 4, 10, 11, 12, 13, 14, 15, 16, 17], crc_extra: 245 },
+        211: { format: '<QQQQffffffffffI', type: mavlink10.messages.payload_stats_tm, order_map: [0, 4, 1, 5, 2, 6, 7, 8, 3, 9, 10, 11, 12, 13, 14], crc_extra: 115 },
+        212: { format: '<QffffffBBBBBBBBBB', type: mavlink10.messages.gse_tm, order_map: [0, 1, 2, 3, 4, 7, 8, 9, 10, 11, 12, 13, 5, 6, 14, 15, 16], crc_extra: 63 },
+        213: { format: '<QffffffBBB', type: mavlink10.messages.motor_tm, order_map: [0, 1, 2, 3, 7, 4, 8, 9, 5, 6], crc_extra: 79 },
+}
+
+
+// Special mavlink message to capture malformed data packets for debugging
+mavlink10.messages.bad_data = function(data, reason) {
+    this._id = mavlink10.MAVLINK_MSG_ID_BAD_DATA;
+    this._data = data;
+    this._reason = reason;
+    this._msgbuf = data;
+}
+mavlink10.messages.bad_data.prototype = new mavlink10.message;
+
+//  MAVLink signing state class
+MAVLinkSigning = function MAVLinkSigning(object){ 
+        this.secret_key = new Buffer.from([]) ; //new Buffer.from([ 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42, 42 ]) // secret key must be a Buffer obj of 32 length 
+        this.timestamp = 1 
+        this.link_id = 0 
+        this.sign_outgoing = false // todo false this 
+        this.allow_unsigned_callback = undefined 
+        this.stream_timestamps = {} 
+        this.sig_count = 0 
+        this.badsig_count = 0 
+        this.goodsig_count = 0 
+        this.unsigned_count = 0 
+        this.reject_count = 0 
+} 
+
+/* MAVLink protocol handling class */
+MAVLink10Processor = function(logger, srcSystem, srcComponent) {
+
+    this.logger = logger;
+
+    this.seq = 0;
+    this.buf = new Buffer.from([]);
+    this.bufInError = new Buffer.from([]);
+   
+    this.srcSystem = (typeof srcSystem === 'undefined') ? 0 : srcSystem;
+    this.srcComponent =  (typeof srcComponent === 'undefined') ? 0 : srcComponent;
+
+    this.have_prefix_error = false;
+
+    // The first packet we expect is a valid header, 6 bytes.
+    this.protocol_marker = 254;   
+    this.expected_length = mavlink10.HEADER_LEN;
+    this.little_endian = true;
+
+    this.crc_extra = true;
+    this.sort_fields = true;
+    this.total_packets_sent = 0;
+    this.total_bytes_sent = 0;
+    this.total_packets_received = 0;
+    this.total_bytes_received = 0;
+    this.total_receive_errors = 0;
+    this.startup_time = Date.now();
+
+    // optional , but when used we store signing state in this object: 
+    this.signing = new MAVLinkSigning();
+}
+
+// Implements EventEmitter
+util.inherits(MAVLink10Processor, events.EventEmitter);
+
+// If the logger exists, this function will add a message to it.
+// Assumes the logger is a winston object.
+MAVLink10Processor.prototype.log = function(message) {
+    if(this.logger) {
+        this.logger.info(message);
+    }
+}
+
+MAVLink10Processor.prototype.log = function(level, message) {
+    if(this.logger) {
+        this.logger.log(level, message);
+    }
+}
+
+MAVLink10Processor.prototype.send = function(mavmsg) {
+    buf = mavmsg.pack(this);
+    this.file.write(buf);
+    this.seq = (this.seq + 1) % 256;
+    this.total_packets_sent +=1;
+    this.total_bytes_sent += buf.length;
+}
+
+// return number of bytes needed for next parsing stage
+MAVLink10Processor.prototype.bytes_needed = function() {
+    ret = this.expected_length - this.buf.length;
+    return ( ret <= 0 ) ? 1 : ret;
+}
+
+// add data to the local buffer
+MAVLink10Processor.prototype.pushBuffer = function(data) {
+    if(data) {
+        this.buf = Buffer.concat([this.buf, data]);   // python calls this self.buf.extend(c) 
+        this.total_bytes_received += data.length;
+    }
+}
+
+// Decode prefix.  Elides the prefix.
+MAVLink10Processor.prototype.parsePrefix = function() {
+
+    // Test for a message prefix.
+    if( this.buf.length >= 1 && this.buf[0] != this.protocol_marker ) {
+
+        // Strip the offending initial byte and throw an error.
+        var badPrefix = this.buf[0];
+        this.bufInError = this.buf.slice(0,1);
+        this.buf = this.buf.slice(1);
+        this.expected_length = mavlink10.HEADER_LEN; //initially we 'expect' at least the length of the header, later parseLength corrects for this. 
+        throw new Error("Bad prefix ("+badPrefix+")");
+    }
+
+}
+
+// Determine the length.  Leaves buffer untouched.
+// Although the 'len' of a packet is available as of the second byte, the third byte with 'incompat_flags' lets
+//  us know if we have signing enabled, which affects the real-world length by the signature-block length of 13 bytes.
+// once successful, 'this.expected_length' is correctly set for the whole packet.
+MAVLink10Processor.prototype.parseLength = function() {
+    
+    if( this.buf.length >= 3 ) { 
+        var unpacked = jspack.Unpack('BBB', this.buf.slice(0, 3)); 
+        var magic = unpacked[0]; // stx ie fd or fe etc 
+        this.expected_length = unpacked[1] + mavlink10.HEADER_LEN + 2 // length of message + header + CRC (ie non-signed length) 
+        this.incompat_flags = unpacked[2];  
+        // mavlink2 only..  in mavlink1, incompat_flags var above is actually the 'seq', but for this test its ok. 
+        if ((magic == mavlink10.PROTOCOL_MARKER_V2 ) && ( this.incompat_flags & mavlink10.MAVLINK_IFLAG_SIGNED )){ 
+            this.expected_length += mavlink10.MAVLINK_SIGNATURE_BLOCK_LEN; 
+        } 
+    }
+
+}
+
+// input some data bytes, possibly returning a new message - python equiv function is called parse_char / __parse_char_legacy 
+MAVLink10Processor.prototype.parseChar = function(c) {
+
+    var m = null;
+
+    try {
+
+        this.pushBuffer(c);
+        this.parsePrefix();
+        this.parseLength();
+        m = this.parsePayload();
+
+    } catch(e) {
+
+        this.log('error', e.message);
+        this.total_receive_errors += 1;
+        m = new mavlink10.messages.bad_data(this.bufInError, e.message);
+        this.bufInError = new Buffer.from([]);
+        
+    }
+
+    // emit a packet-specific message as well as a generic message, user/s can choose to use either or both of these.
+    if(null != m) {
+        this.emit(m._name, m);
+        this.emit('message', m);
+    }
+
+    return m;
+
+}
+
+// continuation of python's  __parse_char_legacy 
+MAVLink10Processor.prototype.parsePayload = function() {
+
+    var m = null;
+
+    // tip: this.expected_length and this.incompat_flags both already set correctly by parseLength(..) above 
+
+    // If we have enough bytes to try and read it, read it.  
+    //  shortest packet is header+checksum(2) with no payload, so we need at least that many 
+    //  but once we have a longer 'expected length' we have to read all of it. 
+    if(( this.expected_length >= mavlink10.HEADER_LEN+2) && (this.buf.length >= this.expected_length) ) { 
+
+        // Slice off the expected packet length, reset expectation to be to find a header.
+        var mbuf = this.buf.slice(0, this.expected_length);
+
+        // TODO: slicing off the buffer should depend on the error produced by the decode() function
+        // - if we find a well formed message, cut-off the expected_length 
+        // - if the message is not well formed (correct prefix by accident), cut-off 1 char only
+        this.buf = this.buf.slice(this.expected_length);
+        this.expected_length = mavlink10.HEADER_LEN; // after attempting a parse, we'll next expect to find just a header. 
+
+        try {
+            m = this.decode(mbuf);
+            this.total_packets_received += 1;
+        }
+        catch(e) {
+            // Set buffer in question and re-throw to generic error handling
+            this.bufInError = mbuf;
+            throw e;
+        }
+    }
+
+    return m;
+
+}
+
+// input some data bytes, possibly returning an array of new messages
+MAVLink10Processor.prototype.parseBuffer = function(s) {
+    
+    // Get a message, if one is available in the stream.
+    var m = this.parseChar(s);
+
+    // No messages available, bail.
+    if ( null === m ) {
+        return null;
+    }
+    
+    // While more valid messages can be read from the existing buffer, add
+    // them to the array of new messages and return them.
+    var ret = [m];
+    while(true) {
+        m = this.parseChar();
+        if ( null === m ) {
+            // No more messages left.
+            return ret;
+        }
+        ret.push(m);
+    }
+
+}
+
+// from Buffer to ArrayBuffer 
+function toArrayBuffer(buf) { 
+    var ab = new ArrayBuffer(buf.length); 
+    var view = new Uint8Array(ab); 
+    for (var i = 0; i < buf.length; ++i) { 
+        view[i] = buf[i]; 
+    } 
+    return ab; 
+} 
+// and back 
+function toBuffer(ab) { 
+    var buf = Buffer.alloc(ab.byteLength); 
+    var view = new Uint8Array(ab); 
+    for (var i = 0; i < buf.length; ++i) { 
+        buf[i] = view[i]; 
+    } 
+    return buf; 
+} 
+ 
+//check signature on incoming message , many of the comments in this file come from the python impl
+MAVLink10Processor.prototype.check_signature = function(msgbuf, srcSystem, srcComponent) { 
+
+        //if (isinstance(msgbuf, array.array)){ 
+        //    msgbuf = msgbuf.tostring() 
+        //} 
+        if ( Buffer.isBuffer(msgbuf) ) { 
+            msgbuf = toArrayBuffer(msgbuf); 
+        } 
+ 
+        //timestamp_buf = msgbuf[-12:-6] 
+        var timestamp_buf= msgbuf.slice(-12,-6);  
+ 
+        //link_id = msgbuf[-13] 
+        var link_id= new Buffer.from(msgbuf.slice(-13,-12)); // just a single byte really, but returned as a buffer 
+        link_id = link_id[0]; // get the first byte.
+ 
+        //self.mav_sign_unpacker = jspack.Unpack('<IH') 
+        // (tlow, thigh) = self.mav_sign_unpacker.unpack(timestamp_buf) 
+
+        // I means unsigned 4bytes, H means unsigned 2 bytes
+        var t = jspack.Unpack('<IH',new Buffer.from(timestamp_buf))  
+        const [tlow, thigh]  = t; 
+ 
+        // due to js not being able to shift numbers  more than 32, we'll use this instead.. 
+        // js stores all its numbers as a 64bit float with 53 bits of mantissa, so have room for 48 ok. 
+        function shift(number, shift) { 
+            return number * Math.pow(2, shift); 
+        } 
+        var thigh_shifted = shift(thigh,32);  
+        var timestamp = tlow + thigh_shifted 
+ 
+        // see if the timestamp is acceptable 
+ 
+         // we'll use a STRING containing these three things in it as a unique key eg: '0,1,1' 
+        stream_key = new Array(link_id,srcSystem,srcComponent).toString(); 
+ 
+        if (stream_key in this.signing.stream_timestamps){ 
+            if (timestamp <= this.signing.stream_timestamps[stream_key]){ 
+                //# reject old timestamp 
+                //console.log('old timestamp')  
+                return false 
+            } 
+        }else{ 
+            //# a new stream has appeared. Accept the timestamp if it is at most 
+            //# one minute behind our current timestamp 
+            if (timestamp + 6000*1000 < this.signing.timestamp){ 
+                //console.log('bad new stream ', timestamp/(100.0*1000*60*60*24*365), this.signing.timestamp/(100.0*1000*60*60*24*365))  
+                return false 
+            } 
+            this.signing.stream_timestamps[stream_key] = timestamp; 
+            //console.log('new stream',this.signing.stream_timestamps)  
+        } 
+ 
+         //   h = hashlib.new('sha256') 
+         //   h.update(this.signing.secret_key) 
+         //   h.update(msgbuf[:-6]) 
+        var crypto= require('crypto'); 
+        var h =  crypto.createHash('sha256'); 
+ 
+        // just the last 6 of 13 available are the actual sig . ie excluding the linkid(1) and timestamp(6) 
+        var sigpart = msgbuf.slice(-6); 
+        sigpart = new Buffer.from(sigpart); 
+        // not sig part 0- end-minus-6 
+        var notsigpart = msgbuf.slice(0,-6);  
+        notsigpart = new Buffer.from(notsigpart); 
+
+        h.update(this.signing.secret_key); // secret is already a Buffer 
+        //var tmp = h.copy().digest(); 
+        h.update(notsigpart);  
+        //var tmp2 = h.copy().digest() 
+        var hashDigest = h.digest(); 
+        sig1 = hashDigest.slice(0,6) 
+ 
+        //sig1 = str(h.digest())[:6] 
+        //sig2 = str(msgbuf)[-6:] 
+
+        // can't just compare sigs, need a full buffer compare like this... 
+        //if (sig1 != sigpart){  
+        if (Buffer.compare(sig1,sigpart)){  
+            //console.log('sig mismatch',sig1,sigpart)  
+            return false 
+        } 
+        //# the timestamp we next send with is the max of the received timestamp and 
+        //# our current timestamp 
+        this.signing.timestamp = Math.max(this.signing.timestamp, timestamp) 
+        return true
+} 
+
+/* decode a buffer as a MAVLink message */
+MAVLink10Processor.prototype.decode = function(msgbuf) {
+
+    var magic, incompat_flags, compat_flags, mlen, seq, srcSystem, srcComponent, unpacked, msgId, signature_len; 
+
+    // decode the header
+    try {
+        unpacked = jspack.Unpack('cBBBBB', msgbuf.slice(0, 6));
+        magic = unpacked[0];
+        mlen = unpacked[1];
+        seq = unpacked[2];
+        srcSystem = unpacked[3];
+        srcComponent = unpacked[4];
+        msgId = unpacked[5];
+        }
+    catch(e) {
+        throw new Error('Unable to unpack MAVLink header: ' + e.message);
+    }
+
+    //  TODO allow full parsing of 1.0 inside the 2.0 parser, this is just a start 
+    if (magic == mavlink10.PROTOCOL_MARKER_V1){ 
+            //headerlen = 6; 
+             
+            // these two are in the same place in both v1 and v2 so no change needed: 
+            //magic = magic; 
+            //mlen = mlen; 
+ 
+            // grab mavlink-v1 header position info from v2 unpacked position 
+            seq1 = incompat_flags; 
+            srcSystem1 = compat_flags; 
+            srcComponent1 = seq; 
+            msgId1 = srcSystem; 
+            // override the v1 vs v2 offsets so we get the correct data either way... 
+            seq = seq1; 
+            srcSystem = srcSystem1; 
+            srcComponent = srcComponent1; 
+            msgId = msgId1;  
+            // don't exist in mavlink1, so zero-them 
+            incompat_flags = 0; 
+            compat_flags = 0; 
+            signature_len = 0; 
+            // todo add more v1 here and don't just return 
+            return; 
+    } 
+
+    if (magic.charCodeAt(0) != this.protocol_marker) {
+        throw new Error("Invalid MAVLink prefix ("+magic.charCodeAt(0)+")");
+    }
+
+    // is packet supposed to be signed? 
+    if ( incompat_flags & mavlink10.MAVLINK_IFLAG_SIGNED ){  
+        signature_len = mavlink10.MAVLINK_SIGNATURE_BLOCK_LEN; 
+    } else { 
+        signature_len = 0; 
+    } 
+ 
+    // header's declared len compared to packets actual len 
+    var actual_len = (msgbuf.length - (mavlink10.HEADER_LEN + 2 + signature_len)); 
+    var actual_len_nosign = (msgbuf.length - (mavlink10.HEADER_LEN + 2 )); 
+ 
+    if ((mlen == actual_len) && (signature_len > 0)){ 
+        var len_if_signed = mlen+signature_len; 
+        //console.log("Packet appears signed && labeled as signed, OK. msgId=" + msgId);     
+ 
+    } else  if ((mlen == actual_len_nosign) && (signature_len > 0)){ 
+ 
+        var len_if_signed = mlen+signature_len; 
+        throw new Error("Packet appears unsigned when labeled as signed. Got actual_len "+actual_len_nosign+" expected " + len_if_signed + ", msgId=" + msgId);     
+ 
+    } else if( mlen != actual_len) {  
+          throw new Error("Invalid MAVLink message length.  Got " + (msgbuf.length - (mavlink10.HEADER_LEN + 2)) + " expected " + mlen + ", msgId=" + msgId); 
+
+    }  
+ 
+    if( false === _.has(mavlink10.map, msgId) ) {
+        throw new Error("Unknown MAVLink message ID (" + msgId + ")");
+    }
+
+    // here's the common chunks of packet we want to work with below.. 
+    var headerBuf= msgbuf.slice(mavlink10.HEADER_LEN); // first10 
+    var sigBuf = msgbuf.slice(-signature_len); // last 13 or nothing 
+    var crcBuf1 = msgbuf.slice(-2); // either last-2 or last-2-prior-to-signature 
+    var crcBuf2 = msgbuf.slice(-15,-13); // either last-2 or last-2-prior-to-signature 
+    var payloadBuf = msgbuf.slice(mavlink10.HEADER_LEN, -(signature_len+2)); // the remaining bit between the header and the crc 
+    var crcCheckBuf = msgbuf.slice(1, -(signature_len+2)); // the part uses to calculate the crc - ie between the magic and signature, 
+
+    // decode the payload
+    // refs: (fmt, type, order_map, crc_extra) = mavlink10.map[msgId]
+    var decoder = mavlink10.map[msgId];
+
+    // decode the checksum
+    var receivedChecksum = undefined; 
+    if ( signature_len == 0 ) { // unsigned 
+        try { 
+            receivedChecksum = jspack.Unpack('<H', crcBuf1); 
+        } catch (e) { 
+            throw new Error("Unable to unpack MAVLink unsigned CRC: " + e.message); 
+        } 
+    } else { // signed 
+        try { 
+            receivedChecksum = jspack.Unpack('<H', crcBuf2); 
+        } catch (e) { 
+            throw new Error("Unable to unpack MAVLink signed CRC: " + e.message); 
+        } 
+    }
+    receivedChecksum = receivedChecksum[0]; 
+
+    // make our own chksum of the relevant part of the packet... 
+    var messageChecksum = mavlink10.x25Crc(crcCheckBuf);  
+    var messageChecksum2 = mavlink10.x25Crc([decoder.crc_extra], messageChecksum); 
+ 
+    if ( receivedChecksum != messageChecksum2 ) { 
+        throw new Error('invalid MAVLink CRC in msgID ' +msgId+ ', got 0x' + receivedChecksum + ' checksum, calculated payload checksum as 0x'+messageChecksum2 ); 
+    }
+ 
+    // now check the signature... 
+    var sig_ok = false 
+    if (signature_len == mavlink10.MAVLINK_SIGNATURE_BLOCK_LEN){ 
+        this.signing.sig_count += 1  
+    } 
+
+    // it's a Buffer, zero-length means unused 
+    if (this.signing.secret_key.length != 0 ){ 
+        var accept_signature = false; 
+        if (signature_len == mavlink10.MAVLINK_SIGNATURE_BLOCK_LEN){  
+            sig_ok = this.check_signature(msgbuf, srcSystem, srcComponent); 
+            accept_signature = sig_ok; 
+            if (sig_ok){ 
+                this.signing.goodsig_count += 1 
+            }else{ 
+                this.signing.badsig_count += 1 
+            } 
+            if ( (! accept_signature) && (this.signing.allow_unsigned_callback != undefined) ){ 
+                accept_signature = this.signing.allow_unsigned_callback(this, msgId); 
+                if (accept_signature){ 
+                    this.signing.unsigned_count += 1 
+                }else{ 
+                    this.signing.reject_count += 1 
+                } 
+            } 
+        }else if (this.signing.allow_unsigned_callback != undefined){ 
+            accept_signature = this.signing.allow_unsigned_callback(this, msgId); 
+            if (accept_signature){ 
+                this.signing.unsigned_count += 1 
+            }else{ 
+                this.signing.reject_count += 1 
+            } 
+        } 
+        if (!accept_signature) throw new Error('Invalid signature'); 
+    } 
+
+    // now look at the specifics of the payload... 
+    var paylen = jspack.CalcLength(decoder.format);
+
+        // Decode the payload and reorder the fields to match the order map.
+    try {
+        var t = jspack.Unpack(decoder.format, payloadBuf); 
+    }
+    catch (e) {
+        throw new Error('Unable to unpack MAVLink payload type='+decoder.type+' format='+decoder.format+' payloadLength='+ payloadBuf +': '+ e.message); 
+    }
+
+    // Need to check if the message contains arrays
+    var args = {};
+    const elementsInMsg = decoder.order_map.length;
+    const actualElementsInMsg = JSON.parse(JSON.stringify(t)).length;
+
+    if (elementsInMsg == actualElementsInMsg) {
+        // Reorder the fields to match the order map
+        _.each(t, function(e, i, l) {
+            args[i] = t[decoder.order_map[i]]
+        });
+    } else {
+        // This message contains arrays
+        var typeIndex = 1;
+        var orderIndex = 0;
+        var memberIndex = 0;
+        var tempArgs = {};
+
+        // Walk through the fields 
+        for(var i = 0, size = decoder.format.length-1; i <= size; ++i) {
+            var order = decoder.order_map[orderIndex];
+            var currentType =  decoder.format[typeIndex];
+
+            if (isNaN(parseInt(currentType))) {
+                // This field is not an array check the type and add it to the args
+                tempArgs[orderIndex] = t[memberIndex];
+                memberIndex++;
+            } else {
+                // This field is part of an array, need to find the length of the array
+                var arraySize = ''
+                var newArray = []
+                while (!isNaN(decoder.format[typeIndex])) {
+                    arraySize = arraySize + decoder.format[typeIndex];
+                    typeIndex++;
+                }
+
+                // Now that we know how long the array is, create an array with the values
+                for(var j = 0, size = parseInt(arraySize); j < size; ++j){
+                    newArray.push(t[j+orderIndex]);
+                    memberIndex++;
+                }
+
+                // Add the array to the args object
+                arraySize = arraySize + decoder.format[typeIndex];
+                currentType = arraySize;
+                tempArgs[orderIndex] = newArray;
+            }
+            orderIndex++;
+            typeIndex++;
+        }
+
+        // Finally reorder the fields to match the order map
+        _.each(t, function(e, i, l) {
+            args[i] = tempArgs[decoder.order_map[i]]
+        });
+    }
+
+    
+
+    // construct the message object
+    try {
+        // args at this point might look like:  { '0': 6, '1': 8, '2': 0, '3': 0, '4': 3, '5': 3 }
+        var m = new decoder.type();   // make a new 'empty' instance of the right class,
+        m.set(args,false); // associate ordered-field-numbers to names, after construction not during.
+    }
+    catch (e) {
+        throw new Error('Unable to instantiate MAVLink message of type '+decoder.type+' : ' + e.message);
+    }
+
+    m._signed = sig_ok; 
+    if (m._signed) { m._link_id = msgbuf[-13]; } 
+ 
+    m._msgbuf = msgbuf;
+    m._payload = payloadBuf 
+    m.crc = receivedChecksum;
+    m._header = new mavlink10.header(msgId, mlen, seq, srcSystem, srcComponent, incompat_flags, compat_flags);
+    this.log(m);
+    return m;
+}
+
+
+// allow loading as both common.js (Node), and/or vanilla javascript in-browser
+if(typeof module === "object" && module.exports) {
+    module.exports = {mavlink10, MAVLink10Processor};
+}
+
diff --git a/mavlink_lib.tests.js b/mavlink_lib.tests.js
new file mode 100644
index 0000000000000000000000000000000000000000..34f43de98e62313cec2c6b5f685e7ec80b93009e
--- /dev/null
+++ b/mavlink_lib.tests.js
@@ -0,0 +1,1095 @@
+/*
+TESTS for MAVLink protocol implementation for node.js (auto-generated by mavgen_javascript.py)
+
+Generated from: lyra.xml
+
+Note: this file has been auto-generated. DO NOT EDIT
+*/
+var Long = require('long');
+
+var {mavlink10, MAVLink10Processor} = require('./mavlink.js');
+
+// mock mav with sysid-42 and componentid=150
+let mav = new MAVLink10Processor(null, 42, 150);
+
+// this uses the above mock by default, but lets us override it before or during tests if desired
+let set_mav = function (_mav) {
+    // set global mav var from local
+    mav = _mav;
+};
+exports.set_mav = set_mav;
+
+let verbose = 0; // 0 means not verbose, 1 means a bit more, 2 means most verbose
+let set_verbose = function (_v) {
+    // set global mav var from local
+    verbose = _v;
+};
+exports.set_verbose = set_verbose;
+
+// relevant to how we pass-in the Long object/s to jspack, we'll assume the calling user is smart enough to know that.
+var wrap_long = function (someLong) {
+    return [someLong.getLowBitsUnsigned(), someLong.getHighBitsUnsigned()];
+}
+
+
+let test_ping_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:ping_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:ping_tc          \r'); }
+   var test_ping_tc = new mavlink10.messages.ping_tc(); 
+      test_ping_tc.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+ //var t = new Buffer.from([])
+; //ping_tc
+ var t = new Buffer.from(test_ping_tc.pack(mav));
+   return [test_ping_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_ping_tc = test_ping_tc; // expose in module
+
+let test_command_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:command_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:command_tc          \r'); }
+   var test_command_tc = new mavlink10.messages.command_tc(); 
+      test_command_tc.command_id = 5; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //command_tc
+ var t = new Buffer.from(test_command_tc.pack(mav));
+   return [test_command_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_command_tc = test_command_tc; // expose in module
+
+let test_system_tm_request_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:system_tm_request_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:system_tm_request_tc          \r'); }
+   var test_system_tm_request_tc = new mavlink10.messages.system_tm_request_tc(); 
+      test_system_tm_request_tc.tm_id = 5; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //system_tm_request_tc
+ var t = new Buffer.from(test_system_tm_request_tc.pack(mav));
+   return [test_system_tm_request_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_system_tm_request_tc = test_system_tm_request_tc; // expose in module
+
+let test_sensor_tm_request_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:sensor_tm_request_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:sensor_tm_request_tc          \r'); }
+   var test_sensor_tm_request_tc = new mavlink10.messages.sensor_tm_request_tc(); 
+      test_sensor_tm_request_tc.sensor_name = 5; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //sensor_tm_request_tc
+ var t = new Buffer.from(test_sensor_tm_request_tc.pack(mav));
+   return [test_sensor_tm_request_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_sensor_tm_request_tc = test_sensor_tm_request_tc; // expose in module
+
+let test_servo_tm_request_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:servo_tm_request_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:servo_tm_request_tc          \r'); }
+   var test_servo_tm_request_tc = new mavlink10.messages.servo_tm_request_tc(); 
+      test_servo_tm_request_tc.servo_id = 5; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //servo_tm_request_tc
+ var t = new Buffer.from(test_servo_tm_request_tc.pack(mav));
+   return [test_servo_tm_request_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_servo_tm_request_tc = test_servo_tm_request_tc; // expose in module
+
+let test_set_servo_angle_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_servo_angle_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_servo_angle_tc          \r'); }
+   var test_set_servo_angle_tc = new mavlink10.messages.set_servo_angle_tc(); 
+      test_set_servo_angle_tc.angle = 17.0; // fieldtype: float  isarray: False 
+      test_set_servo_angle_tc.servo_id = 17; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //set_servo_angle_tc
+ var t = new Buffer.from(test_set_servo_angle_tc.pack(mav));
+   return [test_set_servo_angle_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_servo_angle_tc = test_set_servo_angle_tc; // expose in module
+
+let test_wiggle_servo_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:wiggle_servo_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:wiggle_servo_tc          \r'); }
+   var test_wiggle_servo_tc = new mavlink10.messages.wiggle_servo_tc(); 
+      test_wiggle_servo_tc.servo_id = 5; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //wiggle_servo_tc
+ var t = new Buffer.from(test_wiggle_servo_tc.pack(mav));
+   return [test_wiggle_servo_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_wiggle_servo_tc = test_wiggle_servo_tc; // expose in module
+
+let test_reset_servo_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:reset_servo_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:reset_servo_tc          \r'); }
+   var test_reset_servo_tc = new mavlink10.messages.reset_servo_tc(); 
+      test_reset_servo_tc.servo_id = 5; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //reset_servo_tc
+ var t = new Buffer.from(test_reset_servo_tc.pack(mav));
+   return [test_reset_servo_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_reset_servo_tc = test_reset_servo_tc; // expose in module
+
+let test_set_reference_altitude_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_reference_altitude_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_reference_altitude_tc          \r'); }
+   var test_set_reference_altitude_tc = new mavlink10.messages.set_reference_altitude_tc(); 
+      test_set_reference_altitude_tc.ref_altitude = 17.0; // fieldtype: float  isarray: False 
+ //var t = new Buffer.from([])
+; //set_reference_altitude_tc
+ var t = new Buffer.from(test_set_reference_altitude_tc.pack(mav));
+   return [test_set_reference_altitude_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_reference_altitude_tc = test_set_reference_altitude_tc; // expose in module
+
+let test_set_reference_temperature_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_reference_temperature_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_reference_temperature_tc          \r'); }
+   var test_set_reference_temperature_tc = new mavlink10.messages.set_reference_temperature_tc(); 
+      test_set_reference_temperature_tc.ref_temp = 17.0; // fieldtype: float  isarray: False 
+ //var t = new Buffer.from([])
+; //set_reference_temperature_tc
+ var t = new Buffer.from(test_set_reference_temperature_tc.pack(mav));
+   return [test_set_reference_temperature_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_reference_temperature_tc = test_set_reference_temperature_tc; // expose in module
+
+let test_set_orientation_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_orientation_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_orientation_tc          \r'); }
+   var test_set_orientation_tc = new mavlink10.messages.set_orientation_tc(); 
+      test_set_orientation_tc.yaw = 17.0; // fieldtype: float  isarray: False 
+      test_set_orientation_tc.pitch = 45.0; // fieldtype: float  isarray: False 
+      test_set_orientation_tc.roll = 73.0; // fieldtype: float  isarray: False 
+ //var t = new Buffer.from([])
+; //set_orientation_tc
+ var t = new Buffer.from(test_set_orientation_tc.pack(mav));
+   return [test_set_orientation_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_orientation_tc = test_set_orientation_tc; // expose in module
+
+let test_set_coordinates_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_coordinates_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_coordinates_tc          \r'); }
+   var test_set_coordinates_tc = new mavlink10.messages.set_coordinates_tc(); 
+      test_set_coordinates_tc.latitude = 17.0; // fieldtype: float  isarray: False 
+      test_set_coordinates_tc.longitude = 45.0; // fieldtype: float  isarray: False 
+ //var t = new Buffer.from([])
+; //set_coordinates_tc
+ var t = new Buffer.from(test_set_coordinates_tc.pack(mav));
+   return [test_set_coordinates_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_coordinates_tc = test_set_coordinates_tc; // expose in module
+
+let test_raw_event_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:raw_event_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:raw_event_tc          \r'); }
+   var test_raw_event_tc = new mavlink10.messages.raw_event_tc(); 
+      test_raw_event_tc.topic_id = 5; // fieldtype: uint8_t  isarray: False 
+      test_raw_event_tc.event_id = 72; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //raw_event_tc
+ var t = new Buffer.from(test_raw_event_tc.pack(mav));
+   return [test_raw_event_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_raw_event_tc = test_raw_event_tc; // expose in module
+
+let test_set_deployment_altitude_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_deployment_altitude_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_deployment_altitude_tc          \r'); }
+   var test_set_deployment_altitude_tc = new mavlink10.messages.set_deployment_altitude_tc(); 
+      test_set_deployment_altitude_tc.dpl_altitude = 17.0; // fieldtype: float  isarray: False 
+ //var t = new Buffer.from([])
+; //set_deployment_altitude_tc
+ var t = new Buffer.from(test_set_deployment_altitude_tc.pack(mav));
+   return [test_set_deployment_altitude_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_deployment_altitude_tc = test_set_deployment_altitude_tc; // expose in module
+
+let test_set_target_coordinates_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_target_coordinates_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_target_coordinates_tc          \r'); }
+   var test_set_target_coordinates_tc = new mavlink10.messages.set_target_coordinates_tc(); 
+      test_set_target_coordinates_tc.latitude = 17.0; // fieldtype: float  isarray: False 
+      test_set_target_coordinates_tc.longitude = 45.0; // fieldtype: float  isarray: False 
+ //var t = new Buffer.from([])
+; //set_target_coordinates_tc
+ var t = new Buffer.from(test_set_target_coordinates_tc.pack(mav));
+   return [test_set_target_coordinates_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_target_coordinates_tc = test_set_target_coordinates_tc; // expose in module
+
+let test_set_algorithm_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_algorithm_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_algorithm_tc          \r'); }
+   var test_set_algorithm_tc = new mavlink10.messages.set_algorithm_tc(); 
+      test_set_algorithm_tc.algorithm_number = 5; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //set_algorithm_tc
+ var t = new Buffer.from(test_set_algorithm_tc.pack(mav));
+   return [test_set_algorithm_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_algorithm_tc = test_set_algorithm_tc; // expose in module
+
+let test_set_atomic_valve_timing_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_atomic_valve_timing_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_atomic_valve_timing_tc          \r'); }
+   var test_set_atomic_valve_timing_tc = new mavlink10.messages.set_atomic_valve_timing_tc(); 
+      test_set_atomic_valve_timing_tc.maximum_timing = 963497464; // fieldtype: uint32_t  isarray: False 
+      test_set_atomic_valve_timing_tc.servo_id = 17; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //set_atomic_valve_timing_tc
+ var t = new Buffer.from(test_set_atomic_valve_timing_tc.pack(mav));
+   return [test_set_atomic_valve_timing_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_atomic_valve_timing_tc = test_set_atomic_valve_timing_tc; // expose in module
+
+let test_set_valve_maximum_aperture_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_valve_maximum_aperture_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_valve_maximum_aperture_tc          \r'); }
+   var test_set_valve_maximum_aperture_tc = new mavlink10.messages.set_valve_maximum_aperture_tc(); 
+      test_set_valve_maximum_aperture_tc.maximum_aperture = 17.0; // fieldtype: float  isarray: False 
+      test_set_valve_maximum_aperture_tc.servo_id = 17; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //set_valve_maximum_aperture_tc
+ var t = new Buffer.from(test_set_valve_maximum_aperture_tc.pack(mav));
+   return [test_set_valve_maximum_aperture_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_valve_maximum_aperture_tc = test_set_valve_maximum_aperture_tc; // expose in module
+
+let test_conrig_state_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:conrig_state_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:conrig_state_tc          \r'); }
+   var test_conrig_state_tc = new mavlink10.messages.conrig_state_tc(); 
+      test_conrig_state_tc.ignition_btn = 5; // fieldtype: uint8_t  isarray: False 
+      test_conrig_state_tc.filling_valve_btn = 72; // fieldtype: uint8_t  isarray: False 
+      test_conrig_state_tc.venting_valve_btn = 139; // fieldtype: uint8_t  isarray: False 
+      test_conrig_state_tc.release_pressure_btn = 206; // fieldtype: uint8_t  isarray: False 
+      test_conrig_state_tc.quick_connector_btn = 17; // fieldtype: uint8_t  isarray: False 
+      test_conrig_state_tc.start_tars_btn = 84; // fieldtype: uint8_t  isarray: False 
+      test_conrig_state_tc.arm_switch = 151; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //conrig_state_tc
+ var t = new Buffer.from(test_conrig_state_tc.pack(mav));
+   return [test_conrig_state_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_conrig_state_tc = test_conrig_state_tc; // expose in module
+
+let test_set_ignition_time_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_ignition_time_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_ignition_time_tc          \r'); }
+   var test_set_ignition_time_tc = new mavlink10.messages.set_ignition_time_tc(); 
+      test_set_ignition_time_tc.timing = 963497464; // fieldtype: uint32_t  isarray: False 
+ //var t = new Buffer.from([])
+; //set_ignition_time_tc
+ var t = new Buffer.from(test_set_ignition_time_tc.pack(mav));
+   return [test_set_ignition_time_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_ignition_time_tc = test_set_ignition_time_tc; // expose in module
+
+let test_set_stepper_angle_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_stepper_angle_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_stepper_angle_tc          \r'); }
+   var test_set_stepper_angle_tc = new mavlink10.messages.set_stepper_angle_tc(); 
+      test_set_stepper_angle_tc.angle = 17.0; // fieldtype: float  isarray: False 
+      test_set_stepper_angle_tc.stepper_id = 17; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //set_stepper_angle_tc
+ var t = new Buffer.from(test_set_stepper_angle_tc.pack(mav));
+   return [test_set_stepper_angle_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_stepper_angle_tc = test_set_stepper_angle_tc; // expose in module
+
+let test_set_stepper_steps_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_stepper_steps_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_stepper_steps_tc          \r'); }
+   var test_set_stepper_steps_tc = new mavlink10.messages.set_stepper_steps_tc(); 
+      test_set_stepper_steps_tc.steps = 17.0; // fieldtype: float  isarray: False 
+      test_set_stepper_steps_tc.stepper_id = 17; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //set_stepper_steps_tc
+ var t = new Buffer.from(test_set_stepper_steps_tc.pack(mav));
+   return [test_set_stepper_steps_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_stepper_steps_tc = test_set_stepper_steps_tc; // expose in module
+
+let test_ack_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:ack_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:ack_tm          \r'); }
+   var test_ack_tm = new mavlink10.messages.ack_tm(); 
+      test_ack_tm.recv_msgid = 5; // fieldtype: uint8_t  isarray: False 
+      test_ack_tm.seq_ack = 72; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //ack_tm
+ var t = new Buffer.from(test_ack_tm.pack(mav));
+   return [test_ack_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_ack_tm = test_ack_tm; // expose in module
+
+let test_nack_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:nack_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:nack_tm          \r'); }
+   var test_nack_tm = new mavlink10.messages.nack_tm(); 
+      test_nack_tm.recv_msgid = 5; // fieldtype: uint8_t  isarray: False 
+      test_nack_tm.seq_ack = 72; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //nack_tm
+ var t = new Buffer.from(test_nack_tm.pack(mav));
+   return [test_nack_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_nack_tm = test_nack_tm; // expose in module
+
+let test_gps_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:gps_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:gps_tm          \r'); }
+   var test_gps_tm = new mavlink10.messages.gps_tm(); 
+      test_gps_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_gps_tm.latitude = 179.0; // fieldtype: double  isarray: False 
+      test_gps_tm.longitude = 235.0; // fieldtype: double  isarray: False 
+      test_gps_tm.height = 291.0; // fieldtype: double  isarray: False 
+      test_gps_tm.vel_north = 241.0; // fieldtype: float  isarray: False 
+      test_gps_tm.vel_east = 269.0; // fieldtype: float  isarray: False 
+      test_gps_tm.vel_down = 297.0; // fieldtype: float  isarray: False 
+      test_gps_tm.speed = 325.0; // fieldtype: float  isarray: False 
+      test_gps_tm.track = 353.0; // fieldtype: float  isarray: False 
+      test_gps_tm.sensor_name = "ABCDEFGHIJKLMNOPQRS"; // fieldtype: char  isarray: False 
+      test_gps_tm.fix = 221; // fieldtype: uint8_t  isarray: False 
+      test_gps_tm.n_satellites = 32; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //gps_tm
+ var t = new Buffer.from(test_gps_tm.pack(mav));
+   return [test_gps_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_gps_tm = test_gps_tm; // expose in module
+
+let test_imu_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:imu_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:imu_tm          \r'); }
+   var test_imu_tm = new mavlink10.messages.imu_tm(); 
+      test_imu_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_imu_tm.acc_x = 73.0; // fieldtype: float  isarray: False 
+      test_imu_tm.acc_y = 101.0; // fieldtype: float  isarray: False 
+      test_imu_tm.acc_z = 129.0; // fieldtype: float  isarray: False 
+      test_imu_tm.gyro_x = 157.0; // fieldtype: float  isarray: False 
+      test_imu_tm.gyro_y = 185.0; // fieldtype: float  isarray: False 
+      test_imu_tm.gyro_z = 213.0; // fieldtype: float  isarray: False 
+      test_imu_tm.mag_x = 241.0; // fieldtype: float  isarray: False 
+      test_imu_tm.mag_y = 269.0; // fieldtype: float  isarray: False 
+      test_imu_tm.mag_z = 297.0; // fieldtype: float  isarray: False 
+      test_imu_tm.sensor_name = "STUVWXYZABCDEFGHIJK"; // fieldtype: char  isarray: False 
+ //var t = new Buffer.from([])
+; //imu_tm
+ var t = new Buffer.from(test_imu_tm.pack(mav));
+   return [test_imu_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_imu_tm = test_imu_tm; // expose in module
+
+let test_pressure_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:pressure_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:pressure_tm          \r'); }
+   var test_pressure_tm = new mavlink10.messages.pressure_tm(); 
+      test_pressure_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_pressure_tm.pressure = 73.0; // fieldtype: float  isarray: False 
+      test_pressure_tm.sensor_name = "MNOPQRSTUVWXYZABCDE"; // fieldtype: char  isarray: False 
+ //var t = new Buffer.from([])
+; //pressure_tm
+ var t = new Buffer.from(test_pressure_tm.pack(mav));
+   return [test_pressure_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_pressure_tm = test_pressure_tm; // expose in module
+
+let test_adc_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:adc_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:adc_tm          \r'); }
+   var test_adc_tm = new mavlink10.messages.adc_tm(); 
+      test_adc_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_adc_tm.channel_0 = 73.0; // fieldtype: float  isarray: False 
+      test_adc_tm.channel_1 = 101.0; // fieldtype: float  isarray: False 
+      test_adc_tm.channel_2 = 129.0; // fieldtype: float  isarray: False 
+      test_adc_tm.channel_3 = 157.0; // fieldtype: float  isarray: False 
+      test_adc_tm.channel_4 = 185.0; // fieldtype: float  isarray: False 
+      test_adc_tm.channel_5 = 213.0; // fieldtype: float  isarray: False 
+      test_adc_tm.channel_6 = 241.0; // fieldtype: float  isarray: False 
+      test_adc_tm.channel_7 = 269.0; // fieldtype: float  isarray: False 
+      test_adc_tm.sensor_name = "OPQRSTUVWXYZABCDEFG"; // fieldtype: char  isarray: False 
+ //var t = new Buffer.from([])
+; //adc_tm
+ var t = new Buffer.from(test_adc_tm.pack(mav));
+   return [test_adc_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_adc_tm = test_adc_tm; // expose in module
+
+let test_voltage_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:voltage_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:voltage_tm          \r'); }
+   var test_voltage_tm = new mavlink10.messages.voltage_tm(); 
+      test_voltage_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_voltage_tm.voltage = 73.0; // fieldtype: float  isarray: False 
+      test_voltage_tm.sensor_name = "MNOPQRSTUVWXYZABCDE"; // fieldtype: char  isarray: False 
+ //var t = new Buffer.from([])
+; //voltage_tm
+ var t = new Buffer.from(test_voltage_tm.pack(mav));
+   return [test_voltage_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_voltage_tm = test_voltage_tm; // expose in module
+
+let test_current_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:current_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:current_tm          \r'); }
+   var test_current_tm = new mavlink10.messages.current_tm(); 
+      test_current_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_current_tm.current = 73.0; // fieldtype: float  isarray: False 
+      test_current_tm.sensor_name = "MNOPQRSTUVWXYZABCDE"; // fieldtype: char  isarray: False 
+ //var t = new Buffer.from([])
+; //current_tm
+ var t = new Buffer.from(test_current_tm.pack(mav));
+   return [test_current_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_current_tm = test_current_tm; // expose in module
+
+let test_temp_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:temp_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:temp_tm          \r'); }
+   var test_temp_tm = new mavlink10.messages.temp_tm(); 
+      test_temp_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_temp_tm.temperature = 73.0; // fieldtype: float  isarray: False 
+      test_temp_tm.sensor_name = "MNOPQRSTUVWXYZABCDE"; // fieldtype: char  isarray: False 
+ //var t = new Buffer.from([])
+; //temp_tm
+ var t = new Buffer.from(test_temp_tm.pack(mav));
+   return [test_temp_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_temp_tm = test_temp_tm; // expose in module
+
+let test_load_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:load_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:load_tm          \r'); }
+   var test_load_tm = new mavlink10.messages.load_tm(); 
+      test_load_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_load_tm.load = 73.0; // fieldtype: float  isarray: False 
+      test_load_tm.sensor_name = "MNOPQRSTUVWXYZABCDE"; // fieldtype: char  isarray: False 
+ //var t = new Buffer.from([])
+; //load_tm
+ var t = new Buffer.from(test_load_tm.pack(mav));
+   return [test_load_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_load_tm = test_load_tm; // expose in module
+
+let test_attitude_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:attitude_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:attitude_tm          \r'); }
+   var test_attitude_tm = new mavlink10.messages.attitude_tm(); 
+      test_attitude_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_attitude_tm.roll = 73.0; // fieldtype: float  isarray: False 
+      test_attitude_tm.pitch = 101.0; // fieldtype: float  isarray: False 
+      test_attitude_tm.yaw = 129.0; // fieldtype: float  isarray: False 
+      test_attitude_tm.quat_x = 157.0; // fieldtype: float  isarray: False 
+      test_attitude_tm.quat_y = 185.0; // fieldtype: float  isarray: False 
+      test_attitude_tm.quat_z = 213.0; // fieldtype: float  isarray: False 
+      test_attitude_tm.quat_w = 241.0; // fieldtype: float  isarray: False 
+      test_attitude_tm.sensor_name = "KLMNOPQRSTUVWXYZABC"; // fieldtype: char  isarray: False 
+ //var t = new Buffer.from([])
+; //attitude_tm
+ var t = new Buffer.from(test_attitude_tm.pack(mav));
+   return [test_attitude_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_attitude_tm = test_attitude_tm; // expose in module
+
+let test_sensor_state_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:sensor_state_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:sensor_state_tm          \r'); }
+   var test_sensor_state_tm = new mavlink10.messages.sensor_state_tm(); 
+      test_sensor_state_tm.sensor_name = "ABCDEFGHIJKLMNOPQRS"; // fieldtype: char  isarray: False 
+      test_sensor_state_tm.state = 65; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //sensor_state_tm
+ var t = new Buffer.from(test_sensor_state_tm.pack(mav));
+   return [test_sensor_state_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_sensor_state_tm = test_sensor_state_tm; // expose in module
+
+let test_servo_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:servo_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:servo_tm          \r'); }
+   var test_servo_tm = new mavlink10.messages.servo_tm(); 
+      test_servo_tm.servo_position = 17.0; // fieldtype: float  isarray: False 
+      test_servo_tm.servo_id = 17; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //servo_tm
+ var t = new Buffer.from(test_servo_tm.pack(mav));
+   return [test_servo_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_servo_tm = test_servo_tm; // expose in module
+
+let test_pin_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:pin_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:pin_tm          \r'); }
+   var test_pin_tm = new mavlink10.messages.pin_tm(); 
+      test_pin_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_pin_tm.last_change_timestamp = wrap_long(Long.fromString("93372036854776311", true)); // fieldtype: uint64_t  isarray: False 
+      test_pin_tm.pin_id = 53; // fieldtype: uint8_t  isarray: False 
+      test_pin_tm.changes_counter = 120; // fieldtype: uint8_t  isarray: False 
+      test_pin_tm.current_state = 187; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //pin_tm
+ var t = new Buffer.from(test_pin_tm.pack(mav));
+   return [test_pin_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_pin_tm = test_pin_tm; // expose in module
+
+let test_receiver_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:receiver_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:receiver_tm          \r'); }
+   var test_receiver_tm = new mavlink10.messages.receiver_tm(); 
+      test_receiver_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_receiver_tm.main_rx_rssi = 73.0; // fieldtype: float  isarray: False 
+      test_receiver_tm.main_rx_fei = 101.0; // fieldtype: float  isarray: False 
+      test_receiver_tm.payload_rx_rssi = 129.0; // fieldtype: float  isarray: False 
+      test_receiver_tm.payload_rx_fei = 157.0; // fieldtype: float  isarray: False 
+      test_receiver_tm.battery_voltage = 185.0; // fieldtype: float  isarray: False 
+      test_receiver_tm.main_packet_tx_error_count = 18691; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.main_tx_bitrate = 18795; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.main_packet_rx_success_count = 18899; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.main_packet_rx_drop_count = 19003; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.main_rx_bitrate = 19107; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.payload_packet_tx_error_count = 19211; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.payload_tx_bitrate = 19315; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.payload_packet_rx_success_count = 19419; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.payload_packet_rx_drop_count = 19523; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.payload_rx_bitrate = 19627; // fieldtype: uint16_t  isarray: False 
+      test_receiver_tm.main_radio_present = 149; // fieldtype: uint8_t  isarray: False 
+      test_receiver_tm.payload_radio_present = 216; // fieldtype: uint8_t  isarray: False 
+      test_receiver_tm.ethernet_present = 27; // fieldtype: uint8_t  isarray: False 
+      test_receiver_tm.ethernet_status = 94; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //receiver_tm
+ var t = new Buffer.from(test_receiver_tm.pack(mav));
+   return [test_receiver_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_receiver_tm = test_receiver_tm; // expose in module
+
+let test_arp_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:arp_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:arp_tm          \r'); }
+   var test_arp_tm = new mavlink10.messages.arp_tm(); 
+      test_arp_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_arp_tm.yaw = 73.0; // fieldtype: float  isarray: False 
+      test_arp_tm.pitch = 101.0; // fieldtype: float  isarray: False 
+      test_arp_tm.roll = 129.0; // fieldtype: float  isarray: False 
+      test_arp_tm.target_yaw = 157.0; // fieldtype: float  isarray: False 
+      test_arp_tm.target_pitch = 185.0; // fieldtype: float  isarray: False 
+      test_arp_tm.stepperX_pos = 213.0; // fieldtype: float  isarray: False 
+      test_arp_tm.stepperX_delta = 241.0; // fieldtype: float  isarray: False 
+      test_arp_tm.stepperX_speed = 269.0; // fieldtype: float  isarray: False 
+      test_arp_tm.stepperY_pos = 297.0; // fieldtype: float  isarray: False 
+      test_arp_tm.stepperY_delta = 325.0; // fieldtype: float  isarray: False 
+      test_arp_tm.stepperY_speed = 353.0; // fieldtype: float  isarray: False 
+      test_arp_tm.gps_latitude = 381.0; // fieldtype: float  isarray: False 
+      test_arp_tm.gps_longitude = 409.0; // fieldtype: float  isarray: False 
+      test_arp_tm.gps_height = 437.0; // fieldtype: float  isarray: False 
+      test_arp_tm.main_rx_rssi = 465.0; // fieldtype: float  isarray: False 
+      test_arp_tm.battery_voltage = 493.0; // fieldtype: float  isarray: False 
+      test_arp_tm.main_packet_tx_error_count = 20979; // fieldtype: uint16_t  isarray: False 
+      test_arp_tm.main_tx_bitrate = 21083; // fieldtype: uint16_t  isarray: False 
+      test_arp_tm.main_packet_rx_success_count = 21187; // fieldtype: uint16_t  isarray: False 
+      test_arp_tm.main_packet_rx_drop_count = 21291; // fieldtype: uint16_t  isarray: False 
+      test_arp_tm.main_rx_bitrate = 21395; // fieldtype: uint16_t  isarray: False 
+      test_arp_tm.gps_fix = 123; // fieldtype: uint8_t  isarray: False 
+      test_arp_tm.main_radio_present = 190; // fieldtype: uint8_t  isarray: False 
+      test_arp_tm.ethernet_present = 1; // fieldtype: uint8_t  isarray: False 
+      test_arp_tm.ethernet_status = 68; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //arp_tm
+ var t = new Buffer.from(test_arp_tm.pack(mav));
+   return [test_arp_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_arp_tm = test_arp_tm; // expose in module
+
+let test_set_antenna_coordinates_arp_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_antenna_coordinates_arp_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_antenna_coordinates_arp_tc          \r'); }
+   var test_set_antenna_coordinates_arp_tc = new mavlink10.messages.set_antenna_coordinates_arp_tc(); 
+      test_set_antenna_coordinates_arp_tc.latitude = 17.0; // fieldtype: float  isarray: False 
+      test_set_antenna_coordinates_arp_tc.longitude = 45.0; // fieldtype: float  isarray: False 
+ //var t = new Buffer.from([])
+; //set_antenna_coordinates_arp_tc
+ var t = new Buffer.from(test_set_antenna_coordinates_arp_tc.pack(mav));
+   return [test_set_antenna_coordinates_arp_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_antenna_coordinates_arp_tc = test_set_antenna_coordinates_arp_tc; // expose in module
+
+let test_set_rocket_coordinates_arp_tc = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:set_rocket_coordinates_arp_tc'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:set_rocket_coordinates_arp_tc          \r'); }
+   var test_set_rocket_coordinates_arp_tc = new mavlink10.messages.set_rocket_coordinates_arp_tc(); 
+      test_set_rocket_coordinates_arp_tc.latitude = 17.0; // fieldtype: float  isarray: False 
+      test_set_rocket_coordinates_arp_tc.longitude = 45.0; // fieldtype: float  isarray: False 
+ //var t = new Buffer.from([])
+; //set_rocket_coordinates_arp_tc
+ var t = new Buffer.from(test_set_rocket_coordinates_arp_tc.pack(mav));
+   return [test_set_rocket_coordinates_arp_tc,t]; // return an array of unpacked and packed options
+};
+exports.test_set_rocket_coordinates_arp_tc = test_set_rocket_coordinates_arp_tc; // expose in module
+
+let test_sys_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:sys_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:sys_tm          \r'); }
+   var test_sys_tm = new mavlink10.messages.sys_tm(); 
+      test_sys_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_sys_tm.logger = 29; // fieldtype: uint8_t  isarray: False 
+      test_sys_tm.event_broker = 96; // fieldtype: uint8_t  isarray: False 
+      test_sys_tm.radio = 163; // fieldtype: uint8_t  isarray: False 
+      test_sys_tm.pin_observer = 230; // fieldtype: uint8_t  isarray: False 
+      test_sys_tm.sensors = 41; // fieldtype: uint8_t  isarray: False 
+      test_sys_tm.board_scheduler = 108; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //sys_tm
+ var t = new Buffer.from(test_sys_tm.pack(mav));
+   return [test_sys_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_sys_tm = test_sys_tm; // expose in module
+
+let test_fsm_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:fsm_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:fsm_tm          \r'); }
+   var test_fsm_tm = new mavlink10.messages.fsm_tm(); 
+      test_fsm_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_fsm_tm.ada_state = 29; // fieldtype: uint8_t  isarray: False 
+      test_fsm_tm.abk_state = 96; // fieldtype: uint8_t  isarray: False 
+      test_fsm_tm.dpl_state = 163; // fieldtype: uint8_t  isarray: False 
+      test_fsm_tm.fmm_state = 230; // fieldtype: uint8_t  isarray: False 
+      test_fsm_tm.nas_state = 41; // fieldtype: uint8_t  isarray: False 
+      test_fsm_tm.wes_state = 108; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //fsm_tm
+ var t = new Buffer.from(test_fsm_tm.pack(mav));
+   return [test_fsm_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_fsm_tm = test_fsm_tm; // expose in module
+
+let test_logger_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:logger_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:logger_tm          \r'); }
+   var test_logger_tm = new mavlink10.messages.logger_tm(); 
+      test_logger_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_logger_tm.too_large_samples = (new Int32Array([963497880]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.dropped_samples = (new Int32Array([963498088]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.queued_samples = (new Int32Array([963498296]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.buffers_filled = (new Int32Array([963498504]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.buffers_written = (new Int32Array([963498712]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.writes_failed = (new Int32Array([963498920]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.last_write_error = (new Int32Array([963499128]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.average_write_time = (new Int32Array([963499336]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.max_write_time = (new Int32Array([963499544]))[0]; // fieldtype: int32_t  isarray: False 
+      test_logger_tm.log_number = (new Int16Array([19523]))[0]; // fieldtype: int16_t  isarray: False 
+ //var t = new Buffer.from([])
+; //logger_tm
+ var t = new Buffer.from(test_logger_tm.pack(mav));
+   return [test_logger_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_logger_tm = test_logger_tm; // expose in module
+
+let test_mavlink_stats_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:mavlink_stats_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:mavlink_stats_tm          \r'); }
+   var test_mavlink_stats_tm = new mavlink10.messages.mavlink_stats_tm(); 
+      test_mavlink_stats_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_mavlink_stats_tm.parse_state = 963497880; // fieldtype: uint32_t  isarray: False 
+      test_mavlink_stats_tm.n_send_queue = 17859; // fieldtype: uint16_t  isarray: False 
+      test_mavlink_stats_tm.max_send_queue = 17963; // fieldtype: uint16_t  isarray: False 
+      test_mavlink_stats_tm.n_send_errors = 18067; // fieldtype: uint16_t  isarray: False 
+      test_mavlink_stats_tm.packet_rx_success_count = 18171; // fieldtype: uint16_t  isarray: False 
+      test_mavlink_stats_tm.packet_rx_drop_count = 18275; // fieldtype: uint16_t  isarray: False 
+      test_mavlink_stats_tm.msg_received = 199; // fieldtype: uint8_t  isarray: False 
+      test_mavlink_stats_tm.buffer_overrun = 10; // fieldtype: uint8_t  isarray: False 
+      test_mavlink_stats_tm.parse_error = 77; // fieldtype: uint8_t  isarray: False 
+      test_mavlink_stats_tm.packet_idx = 144; // fieldtype: uint8_t  isarray: False 
+      test_mavlink_stats_tm.current_rx_seq = 211; // fieldtype: uint8_t  isarray: False 
+      test_mavlink_stats_tm.current_tx_seq = 22; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //mavlink_stats_tm
+ var t = new Buffer.from(test_mavlink_stats_tm.pack(mav));
+   return [test_mavlink_stats_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_mavlink_stats_tm = test_mavlink_stats_tm; // expose in module
+
+let test_task_stats_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:task_stats_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:task_stats_tm          \r'); }
+   var test_task_stats_tm = new mavlink10.messages.task_stats_tm(); 
+      test_task_stats_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_task_stats_tm.task_min = 73.0; // fieldtype: float  isarray: False 
+      test_task_stats_tm.task_max = 101.0; // fieldtype: float  isarray: False 
+      test_task_stats_tm.task_mean = 129.0; // fieldtype: float  isarray: False 
+      test_task_stats_tm.task_stddev = 157.0; // fieldtype: float  isarray: False 
+      test_task_stats_tm.task_period = 18483; // fieldtype: uint16_t  isarray: False 
+      test_task_stats_tm.task_id = 211; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //task_stats_tm
+ var t = new Buffer.from(test_task_stats_tm.pack(mav));
+   return [test_task_stats_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_task_stats_tm = test_task_stats_tm; // expose in module
+
+let test_ada_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:ada_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:ada_tm          \r'); }
+   var test_ada_tm = new mavlink10.messages.ada_tm(); 
+      test_ada_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_ada_tm.kalman_x0 = 73.0; // fieldtype: float  isarray: False 
+      test_ada_tm.kalman_x1 = 101.0; // fieldtype: float  isarray: False 
+      test_ada_tm.kalman_x2 = 129.0; // fieldtype: float  isarray: False 
+      test_ada_tm.vertical_speed = 157.0; // fieldtype: float  isarray: False 
+      test_ada_tm.msl_altitude = 185.0; // fieldtype: float  isarray: False 
+      test_ada_tm.ref_pressure = 213.0; // fieldtype: float  isarray: False 
+      test_ada_tm.ref_altitude = 241.0; // fieldtype: float  isarray: False 
+      test_ada_tm.ref_temperature = 269.0; // fieldtype: float  isarray: False 
+      test_ada_tm.msl_pressure = 297.0; // fieldtype: float  isarray: False 
+      test_ada_tm.msl_temperature = 325.0; // fieldtype: float  isarray: False 
+      test_ada_tm.dpl_altitude = 353.0; // fieldtype: float  isarray: False 
+      test_ada_tm.state = 161; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //ada_tm
+ var t = new Buffer.from(test_ada_tm.pack(mav));
+   return [test_ada_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_ada_tm = test_ada_tm; // expose in module
+
+let test_nas_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:nas_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:nas_tm          \r'); }
+   var test_nas_tm = new mavlink10.messages.nas_tm(); 
+      test_nas_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_nas_tm.nas_n = 73.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_e = 101.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_d = 129.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_vn = 157.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_ve = 185.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_vd = 213.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_qx = 241.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_qy = 269.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_qz = 297.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_qw = 325.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_bias_x = 353.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_bias_y = 381.0; // fieldtype: float  isarray: False 
+      test_nas_tm.nas_bias_z = 409.0; // fieldtype: float  isarray: False 
+      test_nas_tm.ref_pressure = 437.0; // fieldtype: float  isarray: False 
+      test_nas_tm.ref_temperature = 465.0; // fieldtype: float  isarray: False 
+      test_nas_tm.ref_latitude = 493.0; // fieldtype: float  isarray: False 
+      test_nas_tm.ref_longitude = 521.0; // fieldtype: float  isarray: False 
+      test_nas_tm.state = 233; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //nas_tm
+ var t = new Buffer.from(test_nas_tm.pack(mav));
+   return [test_nas_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_nas_tm = test_nas_tm; // expose in module
+
+let test_mea_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:mea_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:mea_tm          \r'); }
+   var test_mea_tm = new mavlink10.messages.mea_tm(); 
+      test_mea_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_mea_tm.kalman_x0 = 73.0; // fieldtype: float  isarray: False 
+      test_mea_tm.kalman_x1 = 101.0; // fieldtype: float  isarray: False 
+      test_mea_tm.kalman_x2 = 129.0; // fieldtype: float  isarray: False 
+      test_mea_tm.mass = 157.0; // fieldtype: float  isarray: False 
+      test_mea_tm.corrected_pressure = 185.0; // fieldtype: float  isarray: False 
+      test_mea_tm.state = 89; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //mea_tm
+ var t = new Buffer.from(test_mea_tm.pack(mav));
+   return [test_mea_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_mea_tm = test_mea_tm; // expose in module
+
+let test_rocket_flight_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:rocket_flight_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:rocket_flight_tm          \r'); }
+   var test_rocket_flight_tm = new mavlink10.messages.rocket_flight_tm(); 
+      test_rocket_flight_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_rocket_flight_tm.pressure_ada = 73.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.pressure_digi = 101.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.pressure_static = 129.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.pressure_dpl = 157.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.airspeed_pitot = 185.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.altitude_agl = 213.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.ada_vert_speed = 241.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.mea_mass = 269.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.acc_x = 297.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.acc_y = 325.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.acc_z = 353.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.gyro_x = 381.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.gyro_y = 409.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.gyro_z = 437.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.mag_x = 465.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.mag_y = 493.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.mag_z = 521.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.gps_lat = 549.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.gps_lon = 577.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.gps_alt = 605.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.abk_angle = 633.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_n = 661.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_e = 689.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_d = 717.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_vn = 745.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_ve = 773.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_vd = 801.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_qx = 829.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_qy = 857.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_qz = 885.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_qw = 913.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_bias_x = 941.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_bias_y = 969.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.nas_bias_z = 997.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.pin_quick_connector = 1025.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.battery_voltage = 1053.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.cam_battery_voltage = 1081.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.current_consumption = 1109.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.temperature = 1137.0; // fieldtype: float  isarray: False 
+      test_rocket_flight_tm.ada_state = 241; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.fmm_state = 52; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.dpl_state = 119; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.abk_state = 186; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.nas_state = 253; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.mea_state = 64; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.gps_fix = 131; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.pin_launch = 198; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.pin_nosecone = 9; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.pin_expulsion = 76; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.cutter_presence = 143; // fieldtype: uint8_t  isarray: False 
+      test_rocket_flight_tm.logger_error = (new Int8Array([210]))[0]; // fieldtype: int8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //rocket_flight_tm
+ var t = new Buffer.from(test_rocket_flight_tm.pack(mav));
+   return [test_rocket_flight_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_rocket_flight_tm = test_rocket_flight_tm; // expose in module
+
+let test_payload_flight_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:payload_flight_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:payload_flight_tm          \r'); }
+   var test_payload_flight_tm = new mavlink10.messages.payload_flight_tm(); 
+      test_payload_flight_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_payload_flight_tm.pressure_digi = 73.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.pressure_static = 101.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.airspeed_pitot = 129.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.altitude_agl = 157.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.acc_x = 185.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.acc_y = 213.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.acc_z = 241.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.gyro_x = 269.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.gyro_y = 297.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.gyro_z = 325.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.mag_x = 353.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.mag_y = 381.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.mag_z = 409.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.gps_lat = 437.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.gps_lon = 465.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.gps_alt = 493.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.left_servo_angle = 521.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.right_servo_angle = 549.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_n = 577.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_e = 605.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_d = 633.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_vn = 661.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_ve = 689.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_vd = 717.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_qx = 745.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_qy = 773.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_qz = 801.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_qw = 829.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_bias_x = 857.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_bias_y = 885.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.nas_bias_z = 913.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.wes_n = 941.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.wes_e = 969.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.battery_voltage = 997.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.cam_battery_voltage = 1025.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.current_consumption = 1053.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.temperature = 1081.0; // fieldtype: float  isarray: False 
+      test_payload_flight_tm.fmm_state = 217; // fieldtype: uint8_t  isarray: False 
+      test_payload_flight_tm.nas_state = 28; // fieldtype: uint8_t  isarray: False 
+      test_payload_flight_tm.wes_state = 95; // fieldtype: uint8_t  isarray: False 
+      test_payload_flight_tm.gps_fix = 162; // fieldtype: uint8_t  isarray: False 
+      test_payload_flight_tm.pin_nosecone = 229; // fieldtype: uint8_t  isarray: False 
+      test_payload_flight_tm.cutter_presence = 40; // fieldtype: uint8_t  isarray: False 
+      test_payload_flight_tm.logger_error = (new Int8Array([107]))[0]; // fieldtype: int8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //payload_flight_tm
+ var t = new Buffer.from(test_payload_flight_tm.pack(mav));
+   return [test_payload_flight_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_payload_flight_tm = test_payload_flight_tm; // expose in module
+
+let test_rocket_stats_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:rocket_stats_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:rocket_stats_tm          \r'); }
+   var test_rocket_stats_tm = new mavlink10.messages.rocket_stats_tm(); 
+      test_rocket_stats_tm.liftoff_ts = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_rocket_stats_tm.liftoff_max_acc_ts = wrap_long(Long.fromString("93372036854776311", true)); // fieldtype: uint64_t  isarray: False 
+      test_rocket_stats_tm.dpl_ts = wrap_long(Long.fromString("93372036854776815", true)); // fieldtype: uint64_t  isarray: False 
+      test_rocket_stats_tm.max_z_speed_ts = wrap_long(Long.fromString("93372036854777319", true)); // fieldtype: uint64_t  isarray: False 
+      test_rocket_stats_tm.apogee_ts = wrap_long(Long.fromString("93372036854777823", true)); // fieldtype: uint64_t  isarray: False 
+      test_rocket_stats_tm.liftoff_max_acc = 297.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.dpl_max_acc = 325.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.max_z_speed = 353.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.max_airspeed_pitot = 381.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.max_speed_altitude = 409.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.apogee_lat = 437.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.apogee_lon = 465.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.apogee_alt = 493.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.min_pressure = 521.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.ada_min_pressure = 549.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.dpl_vane_max_pressure = 577.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.cpu_load = 605.0; // fieldtype: float  isarray: False 
+      test_rocket_stats_tm.free_heap = 963502040; // fieldtype: uint32_t  isarray: False 
+ //var t = new Buffer.from([])
+; //rocket_stats_tm
+ var t = new Buffer.from(test_rocket_stats_tm.pack(mav));
+   return [test_rocket_stats_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_rocket_stats_tm = test_rocket_stats_tm; // expose in module
+
+let test_payload_stats_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:payload_stats_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:payload_stats_tm          \r'); }
+   var test_payload_stats_tm = new mavlink10.messages.payload_stats_tm(); 
+      test_payload_stats_tm.liftoff_max_acc_ts = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_payload_stats_tm.dpl_ts = wrap_long(Long.fromString("93372036854776311", true)); // fieldtype: uint64_t  isarray: False 
+      test_payload_stats_tm.max_z_speed_ts = wrap_long(Long.fromString("93372036854776815", true)); // fieldtype: uint64_t  isarray: False 
+      test_payload_stats_tm.apogee_ts = wrap_long(Long.fromString("93372036854777319", true)); // fieldtype: uint64_t  isarray: False 
+      test_payload_stats_tm.liftoff_max_acc = 241.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.dpl_max_acc = 269.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.max_z_speed = 297.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.max_airspeed_pitot = 325.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.max_speed_altitude = 353.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.apogee_lat = 381.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.apogee_lon = 409.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.apogee_alt = 437.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.min_pressure = 465.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.cpu_load = 493.0; // fieldtype: float  isarray: False 
+      test_payload_stats_tm.free_heap = 963501208; // fieldtype: uint32_t  isarray: False 
+ //var t = new Buffer.from([])
+; //payload_stats_tm
+ var t = new Buffer.from(test_payload_stats_tm.pack(mav));
+   return [test_payload_stats_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_payload_stats_tm = test_payload_stats_tm; // expose in module
+
+let test_gse_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:gse_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:gse_tm          \r'); }
+   var test_gse_tm = new mavlink10.messages.gse_tm(); 
+      test_gse_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_gse_tm.loadcell_rocket = 73.0; // fieldtype: float  isarray: False 
+      test_gse_tm.loadcell_vessel = 101.0; // fieldtype: float  isarray: False 
+      test_gse_tm.filling_pressure = 129.0; // fieldtype: float  isarray: False 
+      test_gse_tm.vessel_pressure = 157.0; // fieldtype: float  isarray: False 
+      test_gse_tm.battery_voltage = 185.0; // fieldtype: float  isarray: False 
+      test_gse_tm.current_consumption = 213.0; // fieldtype: float  isarray: False 
+      test_gse_tm.arming_state = 101; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.filling_valve_state = 168; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.venting_valve_state = 235; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.release_valve_state = 46; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.main_valve_state = 113; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.ignition_state = 180; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.tars_state = 247; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.main_board_status = 58; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.payload_board_status = 125; // fieldtype: uint8_t  isarray: False 
+      test_gse_tm.motor_board_status = 192; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //gse_tm
+ var t = new Buffer.from(test_gse_tm.pack(mav));
+   return [test_gse_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_gse_tm = test_gse_tm; // expose in module
+
+let test_motor_tm = function () {
+   if ( verbose == 2 ) console.log('test creating and packing:motor_tm'); 
+   if ( verbose == 1) { process.stdout.write('test creating and packing:motor_tm          \r'); }
+   var test_motor_tm = new mavlink10.messages.motor_tm(); 
+      test_motor_tm.timestamp = wrap_long(Long.fromString("93372036854775807", true)); // fieldtype: uint64_t  isarray: False 
+      test_motor_tm.top_tank_pressure = 73.0; // fieldtype: float  isarray: False 
+      test_motor_tm.bottom_tank_pressure = 101.0; // fieldtype: float  isarray: False 
+      test_motor_tm.combustion_chamber_pressure = 129.0; // fieldtype: float  isarray: False 
+      test_motor_tm.tank_temperature = 157.0; // fieldtype: float  isarray: False 
+      test_motor_tm.battery_voltage = 185.0; // fieldtype: float  isarray: False 
+      test_motor_tm.current_consumption = 213.0; // fieldtype: float  isarray: False 
+      test_motor_tm.floating_level = 101; // fieldtype: uint8_t  isarray: False 
+      test_motor_tm.main_valve_state = 168; // fieldtype: uint8_t  isarray: False 
+      test_motor_tm.venting_valve_state = 235; // fieldtype: uint8_t  isarray: False 
+ //var t = new Buffer.from([])
+; //motor_tm
+ var t = new Buffer.from(test_motor_tm.pack(mav));
+   return [test_motor_tm,t]; // return an array of unpacked and packed options
+};
+exports.test_motor_tm = test_motor_tm; // expose in module
+
+mavlink10Tests = function(){ 
+test_ping_tc();
+test_command_tc();
+test_system_tm_request_tc();
+test_sensor_tm_request_tc();
+test_servo_tm_request_tc();
+test_set_servo_angle_tc();
+test_wiggle_servo_tc();
+test_reset_servo_tc();
+test_set_reference_altitude_tc();
+test_set_reference_temperature_tc();
+test_set_orientation_tc();
+test_set_coordinates_tc();
+test_raw_event_tc();
+test_set_deployment_altitude_tc();
+test_set_target_coordinates_tc();
+test_set_algorithm_tc();
+test_set_atomic_valve_timing_tc();
+test_set_valve_maximum_aperture_tc();
+test_conrig_state_tc();
+test_set_ignition_time_tc();
+test_set_stepper_angle_tc();
+test_set_stepper_steps_tc();
+test_ack_tm();
+test_nack_tm();
+test_gps_tm();
+test_imu_tm();
+test_pressure_tm();
+test_adc_tm();
+test_voltage_tm();
+test_current_tm();
+test_temp_tm();
+test_load_tm();
+test_attitude_tm();
+test_sensor_state_tm();
+test_servo_tm();
+test_pin_tm();
+test_receiver_tm();
+test_arp_tm();
+test_set_antenna_coordinates_arp_tc();
+test_set_rocket_coordinates_arp_tc();
+test_sys_tm();
+test_fsm_tm();
+test_logger_tm();
+test_mavlink_stats_tm();
+test_task_stats_tm();
+test_ada_tm();
+test_nas_tm();
+test_mea_tm();
+test_rocket_flight_tm();
+test_payload_flight_tm();
+test_rocket_stats_tm();
+test_payload_stats_tm();
+test_gse_tm();
+test_motor_tm();
+};
+
+// if run as an app, run the tests immediately, but if run as a module don't, require user to call
+if (require.main === module) {
+   verbose=2;  // 0 is not verbose, 1 is a bit, 2 is more.
+   mavlink10Tests();
+} 
+
+
+/* TESTs for MAVLink protocol handling class */
+MAVLink10ProcessorTests = function() { mavlink10Tests(); }
+exports.MAVLink10ProcessorTests = MAVLink10ProcessorTests; // expose in module
+
diff --git a/mavlink_lib/lyra/lyra.h b/mavlink_lib/lyra/lyra.h
index aa09b7c7ddfe2d4e25915f8465aa7e99a5496f9a..93192ef7211db8099cc2691dba44d22078c792eb 100644
--- a/mavlink_lib/lyra/lyra.h
+++ b/mavlink_lib/lyra/lyra.h
@@ -11,7 +11,7 @@
 #endif
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -6834851485668065312
+#define MAVLINK_THIS_XML_HASH 8957901095544637593
 
 #ifdef __cplusplus
 extern "C" {
@@ -246,7 +246,7 @@ typedef enum PinsList
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -6834851485668065312
+#define MAVLINK_THIS_XML_HASH 8957901095544637593
 
 #if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
 # define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
diff --git a/mavlink_lib/lyra/mavlink.h b/mavlink_lib/lyra/mavlink.h
index 20de852be485f52799c1360308e7abec8122a18b..d63aa1ca3de644cb62f684f372c5426abd19e626 100644
--- a/mavlink_lib/lyra/mavlink.h
+++ b/mavlink_lib/lyra/mavlink.h
@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -6834851485668065312
+#define MAVLINK_PRIMARY_XML_HASH 8957901095544637593
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/lyra/version.h b/mavlink_lib/lyra/version.h
index 3eba20e8566c37c8f5823d77a2ed5b11049235d7..f30c2583bb5541b57b590140458e97f2a997f26b 100644
--- a/mavlink_lib/lyra/version.h
+++ b/mavlink_lib/lyra/version.h
@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Sun Dec 10 2023"
+#define MAVLINK_BUILD_DATE "Wed Dec 13 2023"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 176