diff --git a/mavlink_lib.py b/mavlink_lib.py
index 342cb87d49fc3fc61996686a768a36e2eb228f19..a884aec26ddde6d78105db11a4a5bce7dea654dc 100644
--- a/mavlink_lib.py
+++ b/mavlink_lib.py
@@ -1805,23 +1805,23 @@ class MAVLink_arp_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_ARP_TM
         name = 'ARP_TM'
-        fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'target_roll', 'stepperX_steps', 'stepperY_steps', 'stepperX_pos', 'stepperY_pos', 'stepperX_speed', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix']
-        ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'target_roll', 'stepperX_steps', 'stepperY_steps', 'stepperX_pos', 'stepperY_pos', 'stepperX_speed', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t']
+        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']
+        ordered_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']
+        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "target_roll": "deg", "stepperX_steps": "steps", "stepperY_steps": "steps", "stepperX_pos": "steps", "stepperY_pos": "steps", "stepperX_speed": "rps", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m"}
-        format = '<QfffffffffffffffB'
-        native_format = bytearray('<QfffffffffffffffB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 207
-        unpacker = struct.Struct('<QfffffffffffffffB')
+        fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m"}
+        format = '<QffffffffffffffB'
+        native_format = bytearray('<QffffffffffffffB', 'ascii')
+        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 122
+        unpacker = struct.Struct('<QffffffffffffffB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, target_roll, stepperX_steps, stepperY_steps, stepperX_pos, stepperY_pos, stepperX_speed, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix):
+        def __init__(self, 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):
                 MAVLink_message.__init__(self, MAVLink_arp_tm_message.id, MAVLink_arp_tm_message.name)
                 self._fieldnames = MAVLink_arp_tm_message.fieldnames
                 self._instance_field = MAVLink_arp_tm_message.instance_field
@@ -1832,12 +1832,11 @@ class MAVLink_arp_tm_message(MAVLink_message):
                 self.roll = roll
                 self.target_yaw = target_yaw
                 self.target_pitch = target_pitch
-                self.target_roll = target_roll
-                self.stepperX_steps = stepperX_steps
-                self.stepperY_steps = stepperY_steps
                 self.stepperX_pos = stepperX_pos
-                self.stepperY_pos = stepperY_pos
+                self.stepperX_delta = stepperX_delta
                 self.stepperX_speed = stepperX_speed
+                self.stepperY_pos = stepperY_pos
+                self.stepperY_delta = stepperY_delta
                 self.stepperY_speed = stepperY_speed
                 self.gps_latitude = gps_latitude
                 self.gps_longitude = gps_longitude
@@ -1845,7 +1844,7 @@ class MAVLink_arp_tm_message(MAVLink_message):
                 self.gps_fix = gps_fix
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 207, struct.pack('<QfffffffffffffffB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.target_roll, self.stepperX_steps, self.stepperY_steps, self.stepperX_pos, self.stepperY_pos, self.stepperX_speed, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.gps_fix), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 122, struct.pack('<QffffffffffffffB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.gps_fix), force_mavlink1=force_mavlink1)
 
 class MAVLink_set_antenna_coordinates_arp_tc_message(MAVLink_message):
         '''
@@ -3923,7 +3922,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.receiver_tm_encode(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), force_mavlink1=force_mavlink1)
 
-        def arp_tm_encode(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, target_roll, stepperX_steps, stepperY_steps, stepperX_pos, stepperY_pos, stepperX_speed, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix):
+        def arp_tm_encode(self, 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):
                 '''
                 
 
@@ -3933,12 +3932,11 @@ class MAVLink(object):
                 roll                      : Current Roll [deg] (type:float)
                 target_yaw                : Target Yaw [deg] (type:float)
                 target_pitch              : Target Pitch [deg] (type:float)
-                target_roll               : Target Roll [deg] (type:float)
-                stepperX_steps            : StepperX target delta steps [steps] (type:float)
-                stepperY_steps            : StepperY target delta steps [steps] (type:float)
-                stepperX_pos              : StepperX target pos [steps] (type:float)
-                stepperY_pos              : StepperY target pos [steps] (type:float)
+                stepperX_pos              : StepperX current pos [deg] (type:float)
+                stepperX_delta            : StepperX actuated delta [deg] (type:float)
                 stepperX_speed            : StepperX Speed [rps] (type:float)
+                stepperY_pos              : StepperY current pos [deg] (type:float)
+                stepperY_delta            : StepperY actuated delta [deg] (type:float)
                 stepperY_speed            : StepperY Speed [rps] (type:float)
                 gps_latitude              : Latitude [deg] (type:float)
                 gps_longitude             : Longitude [deg] (type:float)
@@ -3946,9 +3944,9 @@ class MAVLink(object):
                 gps_fix                   : Wether the GPS has a FIX (type:uint8_t)
 
                 '''
-                return MAVLink_arp_tm_message(timestamp, yaw, pitch, roll, target_yaw, target_pitch, target_roll, stepperX_steps, stepperY_steps, stepperX_pos, stepperY_pos, stepperX_speed, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix)
+                return MAVLink_arp_tm_message(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)
 
-        def arp_tm_send(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, target_roll, stepperX_steps, stepperY_steps, stepperX_pos, stepperY_pos, stepperX_speed, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, force_mavlink1=False):
+        def arp_tm_send(self, 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, force_mavlink1=False):
                 '''
                 
 
@@ -3958,12 +3956,11 @@ class MAVLink(object):
                 roll                      : Current Roll [deg] (type:float)
                 target_yaw                : Target Yaw [deg] (type:float)
                 target_pitch              : Target Pitch [deg] (type:float)
-                target_roll               : Target Roll [deg] (type:float)
-                stepperX_steps            : StepperX target delta steps [steps] (type:float)
-                stepperY_steps            : StepperY target delta steps [steps] (type:float)
-                stepperX_pos              : StepperX target pos [steps] (type:float)
-                stepperY_pos              : StepperY target pos [steps] (type:float)
+                stepperX_pos              : StepperX current pos [deg] (type:float)
+                stepperX_delta            : StepperX actuated delta [deg] (type:float)
                 stepperX_speed            : StepperX Speed [rps] (type:float)
+                stepperY_pos              : StepperY current pos [deg] (type:float)
+                stepperY_delta            : StepperY actuated delta [deg] (type:float)
                 stepperY_speed            : StepperY Speed [rps] (type:float)
                 gps_latitude              : Latitude [deg] (type:float)
                 gps_longitude             : Longitude [deg] (type:float)
@@ -3971,7 +3968,7 @@ class MAVLink(object):
                 gps_fix                   : Wether the GPS has a FIX (type:uint8_t)
 
                 '''
-                return self.send(self.arp_tm_encode(timestamp, yaw, pitch, roll, target_yaw, target_pitch, target_roll, stepperX_steps, stepperY_steps, stepperX_pos, stepperY_pos, stepperX_speed, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix), force_mavlink1=force_mavlink1)
+                return self.send(self.arp_tm_encode(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), force_mavlink1=force_mavlink1)
 
         def set_antenna_coordinates_arp_tc_encode(self, latitude, longitude):
                 '''
diff --git a/mavlink_lib/lyra/lyra.h b/mavlink_lib/lyra/lyra.h
index f951593e0daf7ab13a55ccb6bce7a4a609b174c2..856050d9a13f0c18e07ab1cc8cdf24f613283569 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 2380634962514379620
+#define MAVLINK_THIS_XML_HASH -9018180599407197224
 
 #ifdef __cplusplus
 extern "C" {
@@ -20,11 +20,11 @@ extern "C" {
 // MESSAGE LENGTHS AND CRCS
 
 #ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 5, 5, 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, 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, 2, 2, 74, 64, 32, 60, 32, 32, 32, 32, 56, 21, 5, 19, 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, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 69, 8, 8, 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, 14, 14, 46, 28, 27, 53, 77, 29, 176, 163, 92, 76, 42, 35, 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}
+#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 5, 5, 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, 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, 2, 2, 74, 64, 32, 60, 32, 32, 32, 32, 56, 21, 5, 19, 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, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 65, 8, 8, 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, 14, 14, 46, 28, 27, 53, 77, 29, 176, 163, 92, 76, 42, 35, 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}
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 180, 246, 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, 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, 50, 146, 57, 72, 87, 229, 245, 212, 140, 148, 6, 155, 87, 255, 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, 117, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 207, 202, 164, 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, 183, 242, 142, 108, 133, 234, 66, 11, 214, 84, 245, 115, 63, 79, 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}
+#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 180, 246, 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, 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, 50, 146, 57, 72, 87, 229, 245, 212, 140, 148, 6, 155, 87, 255, 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, 117, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 122, 202, 164, 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, 183, 242, 142, 108, 133, 234, 66, 11, 214, 84, 245, 115, 63, 79, 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}
 #endif
 
 #include "../protocol.h"
@@ -246,7 +246,7 @@ typedef enum PinsList
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 2380634962514379620
+#define MAVLINK_THIS_XML_HASH -9018180599407197224
 
 #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 2a4160249e8678facd0fdb2e8153fb275f1ff222..e9d09c0ef3bfb71896445fb46316037314f1e22b 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 2380634962514379620
+#define MAVLINK_PRIMARY_XML_HASH -9018180599407197224
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/lyra/mavlink_msg_arp_tm.h b/mavlink_lib/lyra/mavlink_msg_arp_tm.h
index 0358d4d7d44dd6221da05c5afccd115762d73df2..388b3d7d8997287aa3f5208df85eef7507c01cb0 100644
--- a/mavlink_lib/lyra/mavlink_msg_arp_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_arp_tm.h
@@ -11,12 +11,11 @@ typedef struct __mavlink_arp_tm_t {
  float roll; /*< [deg] Current Roll*/
  float target_yaw; /*< [deg] Target Yaw*/
  float target_pitch; /*< [deg] Target Pitch*/
- float target_roll; /*< [deg] Target Roll*/
- float stepperX_steps; /*< [steps] StepperX target delta steps*/
- float stepperY_steps; /*< [steps] StepperY target delta steps*/
- float stepperX_pos; /*< [steps] StepperX target pos*/
- float stepperY_pos; /*< [steps] StepperY target pos*/
+ float stepperX_pos; /*< [deg] StepperX current pos*/
+ float stepperX_delta; /*< [deg] StepperX actuated delta*/
  float stepperX_speed; /*< [rps] StepperX Speed*/
+ float stepperY_pos; /*< [deg] StepperY current pos*/
+ float stepperY_delta; /*< [deg] StepperY actuated delta*/
  float stepperY_speed; /*< [rps] StepperY Speed*/
  float gps_latitude; /*< [deg] Latitude*/
  float gps_longitude; /*< [deg] Longitude*/
@@ -24,13 +23,13 @@ typedef struct __mavlink_arp_tm_t {
  uint8_t gps_fix; /*<  Wether the GPS has a FIX*/
 } mavlink_arp_tm_t;
 
-#define MAVLINK_MSG_ID_ARP_TM_LEN 69
-#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 69
-#define MAVLINK_MSG_ID_169_LEN 69
-#define MAVLINK_MSG_ID_169_MIN_LEN 69
+#define MAVLINK_MSG_ID_ARP_TM_LEN 65
+#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 65
+#define MAVLINK_MSG_ID_169_LEN 65
+#define MAVLINK_MSG_ID_169_MIN_LEN 65
 
-#define MAVLINK_MSG_ID_ARP_TM_CRC 207
-#define MAVLINK_MSG_ID_169_CRC 207
+#define MAVLINK_MSG_ID_ARP_TM_CRC 122
+#define MAVLINK_MSG_ID_169_CRC 122
 
 
 
@@ -38,47 +37,45 @@ typedef struct __mavlink_arp_tm_t {
 #define MAVLINK_MESSAGE_INFO_ARP_TM { \
     169, \
     "ARP_TM", \
-    17, \
+    16, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \
          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \
          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \
          { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_arp_tm_t, roll) }, \
          { "target_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_arp_tm_t, target_yaw) }, \
          { "target_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_arp_tm_t, target_pitch) }, \
-         { "target_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_arp_tm_t, target_roll) }, \
-         { "stepperX_steps", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_arp_tm_t, stepperX_steps) }, \
-         { "stepperY_steps", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_arp_tm_t, stepperY_steps) }, \
-         { "stepperX_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_arp_tm_t, stepperX_pos) }, \
-         { "stepperY_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_arp_tm_t, stepperY_pos) }, \
-         { "stepperX_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_arp_tm_t, stepperX_speed) }, \
-         { "stepperY_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, stepperY_speed) }, \
-         { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
-         { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
-         { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, gps_height) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 68, offsetof(mavlink_arp_tm_t, gps_fix) }, \
+         { "stepperX_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_arp_tm_t, stepperX_pos) }, \
+         { "stepperX_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_arp_tm_t, stepperX_delta) }, \
+         { "stepperX_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_arp_tm_t, stepperX_speed) }, \
+         { "stepperY_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_arp_tm_t, stepperY_pos) }, \
+         { "stepperY_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_arp_tm_t, stepperY_delta) }, \
+         { "stepperY_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_arp_tm_t, stepperY_speed) }, \
+         { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
+         { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
+         { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_arp_tm_t, gps_fix) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ARP_TM { \
     "ARP_TM", \
-    17, \
+    16, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \
          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \
          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \
          { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_arp_tm_t, roll) }, \
          { "target_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_arp_tm_t, target_yaw) }, \
          { "target_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_arp_tm_t, target_pitch) }, \
-         { "target_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_arp_tm_t, target_roll) }, \
-         { "stepperX_steps", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_arp_tm_t, stepperX_steps) }, \
-         { "stepperY_steps", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_arp_tm_t, stepperY_steps) }, \
-         { "stepperX_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_arp_tm_t, stepperX_pos) }, \
-         { "stepperY_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_arp_tm_t, stepperY_pos) }, \
-         { "stepperX_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_arp_tm_t, stepperX_speed) }, \
-         { "stepperY_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, stepperY_speed) }, \
-         { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
-         { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
-         { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, gps_height) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 68, offsetof(mavlink_arp_tm_t, gps_fix) }, \
+         { "stepperX_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_arp_tm_t, stepperX_pos) }, \
+         { "stepperX_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_arp_tm_t, stepperX_delta) }, \
+         { "stepperX_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_arp_tm_t, stepperX_speed) }, \
+         { "stepperY_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_arp_tm_t, stepperY_pos) }, \
+         { "stepperY_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_arp_tm_t, stepperY_delta) }, \
+         { "stepperY_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_arp_tm_t, stepperY_speed) }, \
+         { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
+         { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
+         { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_arp_tm_t, gps_fix) }, \
          } \
 }
 #endif
@@ -95,12 +92,11 @@ typedef struct __mavlink_arp_tm_t {
  * @param roll [deg] Current Roll
  * @param target_yaw [deg] Target Yaw
  * @param target_pitch [deg] Target Pitch
- * @param target_roll [deg] Target Roll
- * @param stepperX_steps [steps] StepperX target delta steps
- * @param stepperY_steps [steps] StepperY target delta steps
- * @param stepperX_pos [steps] StepperX target pos
- * @param stepperY_pos [steps] StepperY target pos
+ * @param stepperX_pos [deg] StepperX current pos
+ * @param stepperX_delta [deg] StepperX actuated delta
  * @param stepperX_speed [rps] StepperX Speed
+ * @param stepperY_pos [deg] StepperY current pos
+ * @param stepperY_delta [deg] StepperY actuated delta
  * @param stepperY_speed [rps] StepperY Speed
  * @param gps_latitude [deg] Latitude
  * @param gps_longitude [deg] Longitude
@@ -109,7 +105,7 @@ typedef struct __mavlink_arp_tm_t {
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float target_roll, float stepperX_steps, float stepperY_steps, float stepperX_pos, float stepperY_pos, float stepperX_speed, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix)
+                               uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -119,17 +115,16 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_float(buf, 16, roll);
     _mav_put_float(buf, 20, target_yaw);
     _mav_put_float(buf, 24, target_pitch);
-    _mav_put_float(buf, 28, target_roll);
-    _mav_put_float(buf, 32, stepperX_steps);
-    _mav_put_float(buf, 36, stepperY_steps);
-    _mav_put_float(buf, 40, stepperX_pos);
-    _mav_put_float(buf, 44, stepperY_pos);
-    _mav_put_float(buf, 48, stepperX_speed);
-    _mav_put_float(buf, 52, stepperY_speed);
-    _mav_put_float(buf, 56, gps_latitude);
-    _mav_put_float(buf, 60, gps_longitude);
-    _mav_put_float(buf, 64, gps_height);
-    _mav_put_uint8_t(buf, 68, gps_fix);
+    _mav_put_float(buf, 28, stepperX_pos);
+    _mav_put_float(buf, 32, stepperX_delta);
+    _mav_put_float(buf, 36, stepperX_speed);
+    _mav_put_float(buf, 40, stepperY_pos);
+    _mav_put_float(buf, 44, stepperY_delta);
+    _mav_put_float(buf, 48, stepperY_speed);
+    _mav_put_float(buf, 52, gps_latitude);
+    _mav_put_float(buf, 56, gps_longitude);
+    _mav_put_float(buf, 60, gps_height);
+    _mav_put_uint8_t(buf, 64, gps_fix);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
 #else
@@ -140,12 +135,11 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     packet.roll = roll;
     packet.target_yaw = target_yaw;
     packet.target_pitch = target_pitch;
-    packet.target_roll = target_roll;
-    packet.stepperX_steps = stepperX_steps;
-    packet.stepperY_steps = stepperY_steps;
     packet.stepperX_pos = stepperX_pos;
-    packet.stepperY_pos = stepperY_pos;
+    packet.stepperX_delta = stepperX_delta;
     packet.stepperX_speed = stepperX_speed;
+    packet.stepperY_pos = stepperY_pos;
+    packet.stepperY_delta = stepperY_delta;
     packet.stepperY_speed = stepperY_speed;
     packet.gps_latitude = gps_latitude;
     packet.gps_longitude = gps_longitude;
@@ -171,12 +165,11 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
  * @param roll [deg] Current Roll
  * @param target_yaw [deg] Target Yaw
  * @param target_pitch [deg] Target Pitch
- * @param target_roll [deg] Target Roll
- * @param stepperX_steps [steps] StepperX target delta steps
- * @param stepperY_steps [steps] StepperY target delta steps
- * @param stepperX_pos [steps] StepperX target pos
- * @param stepperY_pos [steps] StepperY target pos
+ * @param stepperX_pos [deg] StepperX current pos
+ * @param stepperX_delta [deg] StepperX actuated delta
  * @param stepperX_speed [rps] StepperX Speed
+ * @param stepperY_pos [deg] StepperY current pos
+ * @param stepperY_delta [deg] StepperY actuated delta
  * @param stepperY_speed [rps] StepperY Speed
  * @param gps_latitude [deg] Latitude
  * @param gps_longitude [deg] Longitude
@@ -186,7 +179,7 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
  */
 static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float target_roll,float stepperX_steps,float stepperY_steps,float stepperX_pos,float stepperY_pos,float stepperX_speed,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix)
+                                   uint64_t timestamp,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float stepperX_pos,float stepperX_delta,float stepperX_speed,float stepperY_pos,float stepperY_delta,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -196,17 +189,16 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_float(buf, 16, roll);
     _mav_put_float(buf, 20, target_yaw);
     _mav_put_float(buf, 24, target_pitch);
-    _mav_put_float(buf, 28, target_roll);
-    _mav_put_float(buf, 32, stepperX_steps);
-    _mav_put_float(buf, 36, stepperY_steps);
-    _mav_put_float(buf, 40, stepperX_pos);
-    _mav_put_float(buf, 44, stepperY_pos);
-    _mav_put_float(buf, 48, stepperX_speed);
-    _mav_put_float(buf, 52, stepperY_speed);
-    _mav_put_float(buf, 56, gps_latitude);
-    _mav_put_float(buf, 60, gps_longitude);
-    _mav_put_float(buf, 64, gps_height);
-    _mav_put_uint8_t(buf, 68, gps_fix);
+    _mav_put_float(buf, 28, stepperX_pos);
+    _mav_put_float(buf, 32, stepperX_delta);
+    _mav_put_float(buf, 36, stepperX_speed);
+    _mav_put_float(buf, 40, stepperY_pos);
+    _mav_put_float(buf, 44, stepperY_delta);
+    _mav_put_float(buf, 48, stepperY_speed);
+    _mav_put_float(buf, 52, gps_latitude);
+    _mav_put_float(buf, 56, gps_longitude);
+    _mav_put_float(buf, 60, gps_height);
+    _mav_put_uint8_t(buf, 64, gps_fix);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
 #else
@@ -217,12 +209,11 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.roll = roll;
     packet.target_yaw = target_yaw;
     packet.target_pitch = target_pitch;
-    packet.target_roll = target_roll;
-    packet.stepperX_steps = stepperX_steps;
-    packet.stepperY_steps = stepperY_steps;
     packet.stepperX_pos = stepperX_pos;
-    packet.stepperY_pos = stepperY_pos;
+    packet.stepperX_delta = stepperX_delta;
     packet.stepperX_speed = stepperX_speed;
+    packet.stepperY_pos = stepperY_pos;
+    packet.stepperY_delta = stepperY_delta;
     packet.stepperY_speed = stepperY_speed;
     packet.gps_latitude = gps_latitude;
     packet.gps_longitude = gps_longitude;
@@ -246,7 +237,7 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
 {
-    return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->target_roll, arp_tm->stepperX_steps, arp_tm->stepperY_steps, arp_tm->stepperX_pos, arp_tm->stepperY_pos, arp_tm->stepperX_speed, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix);
+    return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix);
 }
 
 /**
@@ -260,7 +251,7 @@ static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
 {
-    return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->target_roll, arp_tm->stepperX_steps, arp_tm->stepperY_steps, arp_tm->stepperX_pos, arp_tm->stepperY_pos, arp_tm->stepperX_speed, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix);
+    return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix);
 }
 
 /**
@@ -273,12 +264,11 @@ static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t
  * @param roll [deg] Current Roll
  * @param target_yaw [deg] Target Yaw
  * @param target_pitch [deg] Target Pitch
- * @param target_roll [deg] Target Roll
- * @param stepperX_steps [steps] StepperX target delta steps
- * @param stepperY_steps [steps] StepperY target delta steps
- * @param stepperX_pos [steps] StepperX target pos
- * @param stepperY_pos [steps] StepperY target pos
+ * @param stepperX_pos [deg] StepperX current pos
+ * @param stepperX_delta [deg] StepperX actuated delta
  * @param stepperX_speed [rps] StepperX Speed
+ * @param stepperY_pos [deg] StepperY current pos
+ * @param stepperY_delta [deg] StepperY actuated delta
  * @param stepperY_speed [rps] StepperY Speed
  * @param gps_latitude [deg] Latitude
  * @param gps_longitude [deg] Longitude
@@ -287,7 +277,7 @@ static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float target_roll, float stepperX_steps, float stepperY_steps, float stepperX_pos, float stepperY_pos, float stepperX_speed, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix)
+static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -297,17 +287,16 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_float(buf, 16, roll);
     _mav_put_float(buf, 20, target_yaw);
     _mav_put_float(buf, 24, target_pitch);
-    _mav_put_float(buf, 28, target_roll);
-    _mav_put_float(buf, 32, stepperX_steps);
-    _mav_put_float(buf, 36, stepperY_steps);
-    _mav_put_float(buf, 40, stepperX_pos);
-    _mav_put_float(buf, 44, stepperY_pos);
-    _mav_put_float(buf, 48, stepperX_speed);
-    _mav_put_float(buf, 52, stepperY_speed);
-    _mav_put_float(buf, 56, gps_latitude);
-    _mav_put_float(buf, 60, gps_longitude);
-    _mav_put_float(buf, 64, gps_height);
-    _mav_put_uint8_t(buf, 68, gps_fix);
+    _mav_put_float(buf, 28, stepperX_pos);
+    _mav_put_float(buf, 32, stepperX_delta);
+    _mav_put_float(buf, 36, stepperX_speed);
+    _mav_put_float(buf, 40, stepperY_pos);
+    _mav_put_float(buf, 44, stepperY_delta);
+    _mav_put_float(buf, 48, stepperY_speed);
+    _mav_put_float(buf, 52, gps_latitude);
+    _mav_put_float(buf, 56, gps_longitude);
+    _mav_put_float(buf, 60, gps_height);
+    _mav_put_uint8_t(buf, 64, gps_fix);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #else
@@ -318,12 +307,11 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
     packet.roll = roll;
     packet.target_yaw = target_yaw;
     packet.target_pitch = target_pitch;
-    packet.target_roll = target_roll;
-    packet.stepperX_steps = stepperX_steps;
-    packet.stepperY_steps = stepperY_steps;
     packet.stepperX_pos = stepperX_pos;
-    packet.stepperY_pos = stepperY_pos;
+    packet.stepperX_delta = stepperX_delta;
     packet.stepperX_speed = stepperX_speed;
+    packet.stepperY_pos = stepperY_pos;
+    packet.stepperY_delta = stepperY_delta;
     packet.stepperY_speed = stepperY_speed;
     packet.gps_latitude = gps_latitude;
     packet.gps_longitude = gps_longitude;
@@ -342,7 +330,7 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_arp_tm_send_struct(mavlink_channel_t chan, const mavlink_arp_tm_t* arp_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->target_roll, arp_tm->stepperX_steps, arp_tm->stepperY_steps, arp_tm->stepperX_pos, arp_tm->stepperY_pos, arp_tm->stepperX_speed, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix);
+    mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)arp_tm, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #endif
@@ -356,7 +344,7 @@ static inline void mavlink_msg_arp_tm_send_struct(mavlink_channel_t chan, const
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float target_roll, float stepperX_steps, float stepperY_steps, float stepperX_pos, float stepperY_pos, float stepperX_speed, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix)
+static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -366,17 +354,16 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_float(buf, 16, roll);
     _mav_put_float(buf, 20, target_yaw);
     _mav_put_float(buf, 24, target_pitch);
-    _mav_put_float(buf, 28, target_roll);
-    _mav_put_float(buf, 32, stepperX_steps);
-    _mav_put_float(buf, 36, stepperY_steps);
-    _mav_put_float(buf, 40, stepperX_pos);
-    _mav_put_float(buf, 44, stepperY_pos);
-    _mav_put_float(buf, 48, stepperX_speed);
-    _mav_put_float(buf, 52, stepperY_speed);
-    _mav_put_float(buf, 56, gps_latitude);
-    _mav_put_float(buf, 60, gps_longitude);
-    _mav_put_float(buf, 64, gps_height);
-    _mav_put_uint8_t(buf, 68, gps_fix);
+    _mav_put_float(buf, 28, stepperX_pos);
+    _mav_put_float(buf, 32, stepperX_delta);
+    _mav_put_float(buf, 36, stepperX_speed);
+    _mav_put_float(buf, 40, stepperY_pos);
+    _mav_put_float(buf, 44, stepperY_delta);
+    _mav_put_float(buf, 48, stepperY_speed);
+    _mav_put_float(buf, 52, gps_latitude);
+    _mav_put_float(buf, 56, gps_longitude);
+    _mav_put_float(buf, 60, gps_height);
+    _mav_put_uint8_t(buf, 64, gps_fix);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #else
@@ -387,12 +374,11 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->roll = roll;
     packet->target_yaw = target_yaw;
     packet->target_pitch = target_pitch;
-    packet->target_roll = target_roll;
-    packet->stepperX_steps = stepperX_steps;
-    packet->stepperY_steps = stepperY_steps;
     packet->stepperX_pos = stepperX_pos;
-    packet->stepperY_pos = stepperY_pos;
+    packet->stepperX_delta = stepperX_delta;
     packet->stepperX_speed = stepperX_speed;
+    packet->stepperY_pos = stepperY_pos;
+    packet->stepperY_delta = stepperY_delta;
     packet->stepperY_speed = stepperY_speed;
     packet->gps_latitude = gps_latitude;
     packet->gps_longitude = gps_longitude;
@@ -470,63 +456,53 @@ static inline float mavlink_msg_arp_tm_get_target_pitch(const mavlink_message_t*
 }
 
 /**
- * @brief Get field target_roll from arp_tm message
+ * @brief Get field stepperX_pos from arp_tm message
  *
- * @return [deg] Target Roll
+ * @return [deg] StepperX current pos
  */
-static inline float mavlink_msg_arp_tm_get_target_roll(const mavlink_message_t* msg)
+static inline float mavlink_msg_arp_tm_get_stepperX_pos(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_float(msg,  28);
 }
 
 /**
- * @brief Get field stepperX_steps from arp_tm message
+ * @brief Get field stepperX_delta from arp_tm message
  *
- * @return [steps] StepperX target delta steps
+ * @return [deg] StepperX actuated delta
  */
-static inline float mavlink_msg_arp_tm_get_stepperX_steps(const mavlink_message_t* msg)
+static inline float mavlink_msg_arp_tm_get_stepperX_delta(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_float(msg,  32);
 }
 
 /**
- * @brief Get field stepperY_steps from arp_tm message
+ * @brief Get field stepperX_speed from arp_tm message
  *
- * @return [steps] StepperY target delta steps
+ * @return [rps] StepperX Speed
  */
-static inline float mavlink_msg_arp_tm_get_stepperY_steps(const mavlink_message_t* msg)
+static inline float mavlink_msg_arp_tm_get_stepperX_speed(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_float(msg,  36);
 }
 
-/**
- * @brief Get field stepperX_pos from arp_tm message
- *
- * @return [steps] StepperX target pos
- */
-static inline float mavlink_msg_arp_tm_get_stepperX_pos(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  40);
-}
-
 /**
  * @brief Get field stepperY_pos from arp_tm message
  *
- * @return [steps] StepperY target pos
+ * @return [deg] StepperY current pos
  */
 static inline float mavlink_msg_arp_tm_get_stepperY_pos(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  44);
+    return _MAV_RETURN_float(msg,  40);
 }
 
 /**
- * @brief Get field stepperX_speed from arp_tm message
+ * @brief Get field stepperY_delta from arp_tm message
  *
- * @return [rps] StepperX Speed
+ * @return [deg] StepperY actuated delta
  */
-static inline float mavlink_msg_arp_tm_get_stepperX_speed(const mavlink_message_t* msg)
+static inline float mavlink_msg_arp_tm_get_stepperY_delta(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  48);
+    return _MAV_RETURN_float(msg,  44);
 }
 
 /**
@@ -536,7 +512,7 @@ static inline float mavlink_msg_arp_tm_get_stepperX_speed(const mavlink_message_
  */
 static inline float mavlink_msg_arp_tm_get_stepperY_speed(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  52);
+    return _MAV_RETURN_float(msg,  48);
 }
 
 /**
@@ -546,7 +522,7 @@ static inline float mavlink_msg_arp_tm_get_stepperY_speed(const mavlink_message_
  */
 static inline float mavlink_msg_arp_tm_get_gps_latitude(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  56);
+    return _MAV_RETURN_float(msg,  52);
 }
 
 /**
@@ -556,7 +532,7 @@ static inline float mavlink_msg_arp_tm_get_gps_latitude(const mavlink_message_t*
  */
 static inline float mavlink_msg_arp_tm_get_gps_longitude(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  60);
+    return _MAV_RETURN_float(msg,  56);
 }
 
 /**
@@ -566,7 +542,7 @@ static inline float mavlink_msg_arp_tm_get_gps_longitude(const mavlink_message_t
  */
 static inline float mavlink_msg_arp_tm_get_gps_height(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  64);
+    return _MAV_RETURN_float(msg,  60);
 }
 
 /**
@@ -576,7 +552,7 @@ static inline float mavlink_msg_arp_tm_get_gps_height(const mavlink_message_t* m
  */
 static inline uint8_t mavlink_msg_arp_tm_get_gps_fix(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  68);
+    return _MAV_RETURN_uint8_t(msg,  64);
 }
 
 /**
@@ -594,12 +570,11 @@ static inline void mavlink_msg_arp_tm_decode(const mavlink_message_t* msg, mavli
     arp_tm->roll = mavlink_msg_arp_tm_get_roll(msg);
     arp_tm->target_yaw = mavlink_msg_arp_tm_get_target_yaw(msg);
     arp_tm->target_pitch = mavlink_msg_arp_tm_get_target_pitch(msg);
-    arp_tm->target_roll = mavlink_msg_arp_tm_get_target_roll(msg);
-    arp_tm->stepperX_steps = mavlink_msg_arp_tm_get_stepperX_steps(msg);
-    arp_tm->stepperY_steps = mavlink_msg_arp_tm_get_stepperY_steps(msg);
     arp_tm->stepperX_pos = mavlink_msg_arp_tm_get_stepperX_pos(msg);
-    arp_tm->stepperY_pos = mavlink_msg_arp_tm_get_stepperY_pos(msg);
+    arp_tm->stepperX_delta = mavlink_msg_arp_tm_get_stepperX_delta(msg);
     arp_tm->stepperX_speed = mavlink_msg_arp_tm_get_stepperX_speed(msg);
+    arp_tm->stepperY_pos = mavlink_msg_arp_tm_get_stepperY_pos(msg);
+    arp_tm->stepperY_delta = mavlink_msg_arp_tm_get_stepperY_delta(msg);
     arp_tm->stepperY_speed = mavlink_msg_arp_tm_get_stepperY_speed(msg);
     arp_tm->gps_latitude = mavlink_msg_arp_tm_get_gps_latitude(msg);
     arp_tm->gps_longitude = mavlink_msg_arp_tm_get_gps_longitude(msg);
diff --git a/mavlink_lib/lyra/testsuite.h b/mavlink_lib/lyra/testsuite.h
index cb89170ad025c65dec6cacf433f56ae8fc2ea8f2..37e460f282e2b05b61ff731fd7ff31ab137c35a6 100644
--- a/mavlink_lib/lyra/testsuite.h
+++ b/mavlink_lib/lyra/testsuite.h
@@ -2311,7 +2311,7 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_arp_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,209
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,197
     };
     mavlink_arp_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -2321,12 +2321,11 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink
         packet1.roll = packet_in.roll;
         packet1.target_yaw = packet_in.target_yaw;
         packet1.target_pitch = packet_in.target_pitch;
-        packet1.target_roll = packet_in.target_roll;
-        packet1.stepperX_steps = packet_in.stepperX_steps;
-        packet1.stepperY_steps = packet_in.stepperY_steps;
         packet1.stepperX_pos = packet_in.stepperX_pos;
-        packet1.stepperY_pos = packet_in.stepperY_pos;
+        packet1.stepperX_delta = packet_in.stepperX_delta;
         packet1.stepperX_speed = packet_in.stepperX_speed;
+        packet1.stepperY_pos = packet_in.stepperY_pos;
+        packet1.stepperY_delta = packet_in.stepperY_delta;
         packet1.stepperY_speed = packet_in.stepperY_speed;
         packet1.gps_latitude = packet_in.gps_latitude;
         packet1.gps_longitude = packet_in.gps_longitude;
@@ -2346,12 +2345,12 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.target_roll , packet1.stepperX_steps , packet1.stepperY_steps , packet1.stepperX_pos , packet1.stepperY_pos , packet1.stepperX_speed , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix );
+    mavlink_msg_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix );
     mavlink_msg_arp_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.target_roll , packet1.stepperX_steps , packet1.stepperY_steps , packet1.stepperX_pos , packet1.stepperY_pos , packet1.stepperX_speed , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix );
+    mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix );
     mavlink_msg_arp_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2364,7 +2363,7 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.target_roll , packet1.stepperX_steps , packet1.stepperY_steps , packet1.stepperX_pos , packet1.stepperY_pos , packet1.stepperX_speed , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix );
+    mavlink_msg_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix );
     mavlink_msg_arp_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
diff --git a/mavlink_lib/lyra/version.h b/mavlink_lib/lyra/version.h
index e233225489849605130234351e7fff993d9b2990..b53ba52bd18e3a1db05542f25c65594211306357 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 "Sat Dec 02 2023"
+#define MAVLINK_BUILD_DATE "Mon Dec 04 2023"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 176
  
diff --git a/message_definitions/lyra.xml b/message_definitions/lyra.xml
index d475d085c6742b9f6ef3ed54e512365db8303519..013b0004130b58cc156a974aa4d70f75b54c27cf 100644
--- a/message_definitions/lyra.xml
+++ b/message_definitions/lyra.xml
@@ -480,13 +480,12 @@
             <field name="roll" type="float" units="deg">Current Roll</field>
             <field name="target_yaw" type="float" units="deg">Target Yaw</field>
             <field name="target_pitch" type="float" units="deg">Target Pitch</field>
-            <field name="target_roll" type="float" units="deg">Target Roll</field>
-            <field name="stepperX_steps" type="float" units="steps">StepperX target delta steps</field>
-            <field name="stepperY_steps" type="float" units="steps">StepperY target delta steps</field>
-            <field name="stepperX_pos" type="float" units="steps">StepperX target pos</field>
-            <field name="stepperY_pos" type="float" units="steps">StepperY target pos</field>
-            <field name="stepperX_speed" type="float" units="rps">StepperX Speed</field>
-            <field name="stepperY_speed" type="float" units="rps">StepperY Speed</field>
+            <field name="stepperX_pos" type="float" units="deg">StepperX current position wrt the boot position</field>
+            <field name="stepperX_delta" type="float" units="deg">StepperX last actuated delta angle</field>
+            <field name="stepperX_speed" type="float" units="rps">StepperX current speed</field>
+            <field name="stepperY_pos" type="float" units="deg">StepperY current position wrt the boot position</field>
+            <field name="stepperY_delta" type="float" units="deg">StepperY last actuated delta angle</field>
+            <field name="stepperY_speed" type="float" units="rps">StepperY current Speed</field>
             <field name="gps_latitude" type="float" units="deg">Latitude</field>
             <field name="gps_longitude" type="float" units="deg">Longitude</field>
             <field name="gps_height" type="float" units="m">Altitude</field>