MARSH Dialect

This page documents all extensions to MAVLink that were required for the simulator.

The definitions are in the marsh.xml file on the dialect branch in our fork of main MAVLink repository. All other projects need to generate and appropriate libraries, following the mavlink.io – Generating MAVLink Libraries documentation.

When in need of a definition for a given functionality which is not covered here, first consult the Common Message Set, both our subset and full list. If a new definition is actually needed, follow the original guide on how to define MAVLink Messages & Enums

Definition list

Generated on 2024-09-04T13:00:31 from commit c0d8d14

MAVLink Include Files: common.xml

MAVLink Protocol Version

The current MAVLink version is 2.3. The minor version numbers (after the dot) range from 1-255.

This file has protocol dialect: 2.

MAVLink Type Enumerations

MARSH_COMPONENT

[Enum] Component ids (values) for different nodes of the simulator network (flight model, controls, visualisation etc.). Components will always receive messages from the Manager relevant for their ID. Only the first component in a network with a given system ID and component ID will have its messages forwarded by the Manager, all other ones will only be treated as output (will be shadowed). This enum is a redefinition of MAV_COMP_ID_USER# messages from MAV_COMPONENT documented at https://mavlink.io/en/messages/common.html#MAV_COMPONENT

Value Field Name Description
25 MARSH_COMP_ID_MANAGER The simulation manager responsible for routing packets between different nodes. Typically MARSH Manager, see https://marsh-sim.github.io/manager.html
26 MARSH_COMP_ID_FLIGHT_MODEL Component simulating flight dynamics of the aircraft.
27 MARSH_COMP_ID_CONTROLS Component providing pilot control inputs.
28 MARSH_COMP_ID_VISUALISATION Component showing the visual situation to the pilot.
29 MARSH_COMP_ID_INSTRUMENTS Component implementing pilot instrument panel.
30 MARSH_COMP_ID_MOTION_PLATFORM Component that moves the entire cockpit for motion cueing.
31 MARSH_COMP_ID_GSEAT Component for in-seat motion cueing.
32 MARSH_COMP_ID_EYE_TRACKER Component providing gaze data of pilot eyes.
33 MARSH_COMP_ID_CONTROL_LOADING Component measuring and actuating forces on pilot control inputs.

MARSH_MODE_FLAGS

[Enum] These values are MARSH-specific modes intended to be sent in custom_mode field of HEARTBEAT message. Prefer defining values in the most significant byte (between 2^24 and 2^31) to leave the lower three bytes to contain a message id

Value Field Name Description
0x1000000 MARSH_MODE_SINGLE_MESSAGE Request Manager to only send one specific message, advised for very resource limited nodes or with control flow limitations like Simulink. That message id should be in the lower three bytes of the mode, which can be done by adding it to the flags.
0x2000000 MARSH_MODE_ALL_MESSAGES Request Manager to send every message going out to any of the clients.

CONTROL_AXIS

[Enum] Specific axis of pilot control inputs, with order corresponding to x, y, z, r fields in MANUAL_CONTROL message.

Value Field Name Description
0 CONTROL_AXIS_PITCH Pitch axis, with positive values corresponding to stick forward movement, causing the vehicle to move nose down. For helicopters this is longitudinal cyclic.
1 CONTROL_AXIS_ROLL Roll axis, with positive values corresponding to stick right movement, causing the vehicle to roll right. For helicopters this is lateral cyclic.
2 CONTROL_AXIS_THRUST Main thrust, with positive values corresponding to going faster and higher. For helicopters this is collective.
3 CONTROL_AXIS_YAW Yaw axis, with positive values corresponding to pushing right pedal, causing the vehicle to face right direction. For helicopters this is tail collective.

MOTION_PLATFORM_MODE

[Enum] Mode of a motion platform system.

Value Field Name Description
0 MOTION_PLATFORM_MODE_UNKNOWN Mode information is unsupported on this device.
1 MOTION_PLATFORM_MODE_UNINITIALIZED Mode is currently not available, but may be in different condition.
2 MOTION_PLATFORM_MODE_OFF Platform actuators are turned off, but control system is responsive.
3 MOTION_PLATFORM_MODE_SETTLED Platform is in the lowest position and/or locked, appropriate for personnel entry.
4 MOTION_PLATFORM_MODE_NEUTRAL Platform is in a neutral reference position, not accepting movement commands.
5 MOTION_PLATFORM_MODE_FROZEN Platform is stopped in any position, not accepting movement commands.
6 MOTION_PLATFORM_MODE_ENGAGED Platform is in any position, accepting movement commands.

MOTION_PLATFORM_HEALTH

[Enum] General error state of a motion platform system.

Value Field Name Description
0 MOTION_PLATFORM_HEALTH_OK System is operating correctly.
1 MOTION_PLATFORM_HEALTH_WARNING There is at least one warning present, but operation can be continued.
2 MOTION_PLATFORM_HEALTH_ERROR There is a failure or misconfiguration that requires operator's attention for correct operation.
3 MOTION_PLATFORM_HEALTH_CRITICAL There is a major failure that requires immediate operator action to maintain safety.

REXROTH_MOTION_PLATFORM_ERROR

[Enum] Error codes specific to eMotion Motion System from Bosch Rexroth. Details described in GENERIC-02-30-7100-IML-0700 document.

Value Field Name Description
0 REXROTH_ERR_OK No error.
59 REXROTH_ERR_WA_EXCESSIVE_TORQUE_DIFFERENCE
60 REXROTH_ERR_WA_REMOTE_ACCESS_ACTIVE
61 REXROTH_ERR_WA_NON_CRITICAL_CIRCUIT_BREAKER
62 REXROTH_ERR_WA_SEAL_CHECK_POSITION_HIGH
63 REXROTH_ERR_WA_SEAL_CHECK_POSITION_LOW
64 REXROTH_ERR_WA_FRAMECOUNTER_FAIL
65 REXROTH_ERR_WA_UNEXPECTED_STARTUP
75 REXROTH_ERR_WA_UPS_BATTERY_FAIL
77 REXROTH_ERR_WA_PLATFORM_SETTLE_ERROR
88 REXROTH_ERR_WA_BLEEDER_TEMPERATURE
92 REXROTH_ERR_WA_PRESSURE_HIGH
93 REXROTH_ERR_WA_PRESSURE_LOW
94 REXROTH_ERR_WA_BRAKE_UPS_POWER_WARNING
95 REXROTH_ERR_WA_MOTOR_TEMPERATURE_WARNING
96 REXROTH_ERR_FD_FORCED_DISENGAGE_CIRCUIT_OPENED
97 REXROTH_ERR_FD_INVALID_MODE
98 REXROTH_ERR_FD_HOST_DATA_TIME_OUT
99 REXROTH_ERR_FD_FRAMECOUNTER_FAIL
101 REXROTH_ERR_FD_DOORS_AND_PADS_CIRCUIT_OPENED
102 REXROTH_ERR_FD_LOADCHECK_SYSTEM_OVERLOAD
103 REXROTH_ERR_FD_LOADCHECK_ACTUATOR_OVERLOAD
104 REXROTH_ERR_FD_BRAKE_UPS_POWER_ERROR
105 REXROTH_ERR_FD_MOTOR_TEMPERATURE_ERROR
107 REXROTH_ERR_FD_MOTION_ENABLE_CIRCUIT_OPENED
110 REXROTH_ERR_FD_HOST_DATA_INVALID
113 REXROTH_ERR_FD_LOADCHECK_ACTUATOR_UNDERLOAD
115 REXROTH_ERR_FD_SEAL_CHECK_POSITION_TOO_HIGH
116 REXROTH_ERR_FD_SEAL_CHECK_POSITION_TOO_LOW
117 REXROTH_ERR_FD_RAMP_NOT_UP
120 REXROTH_ERR_FD_DRIVE_WARNING
123 REXROTH_ERR_FD_PRESSURE_TOO_HIGH
124 REXROTH_ERR_FD_PRESSURE_TOO_LOW
125 REXROTH_ERR_FD_ACTUATOR_POSITION_DOES_NOT_MATCH_SWITCH_POSITION
126 REXROTH_ERR_FD_SETTLED_SWITCH_NOT_DETECTED_BY_SAFETY_HOMING_PROCEDURE
127 REXROTH_ERR_FD_POWER_OFF_LINE_FAILURE
100 REXROTH_ERR_ES_MOTION_ENABLE_CIRCUIT_OPENED
160 REXROTH_ERR_ES_EMERGENCY_STOP_CIRCUIT_OPENED
164 REXROTH_ERR_ES_RAMP_NOT_UP
172 REXROTH_ERR_ES_MOVE_RAMP_UP_TIMEOUT
173 REXROTH_ERR_ES_MOVE_RAMP_DOWN_TIMEOUT
174 REXROTH_ERR_ES_MOVE_PLATFORM_UP_TIMEOUT
175 REXROTH_ERR_ES_MOVE_PLATFORM_DOWN_TIMEOUT
184 REXROTH_ERR_ES_CIRCUIT_BREAKER
185 REXROTH_ERR_ES_YAW_TABLE_POSITION_LIMIT_ACTIVE
186 REXROTH_ERR_ES_XY_CUSHION
193 REXROTH_ERR_ES_EXCESSIVE_POSITION_DIFFERENCE
194 REXROTH_ERR_ES_BRAKE_POWER_FAIL
195 REXROTH_ERR_ES_MANUAL_BRAKE_RELEASE
206 REXROTH_ERR_ES_RAMP_SWITCH_FAILURE
207 REXROTH_ERR_ES_BUFFER_CHECK_TIMEOUT
208 REXROTH_ERR_ES_BUFFER_CHECK_ERROR
209 REXROTH_ERR_ES_ACTUATOR_POSITION_DOES_NOT_MATCH_SWITCH_POSITION
222 REXROTH_ERR_ES_BB_CONTACT_DRIVE_OPEN
223 REXROTH_ERR_ES_DRIVE_ERROR
225 REXROTH_ERR_ES_POWER_ON_TIMEOUT
226 REXROTH_ERR_ES_POWER_OFF_TIMEOUT
230 REXROTH_ERR_ES_BB_CONTACT_BLEEDER_OPEN
231 REXROTH_ERR_ES_BB_CONTACT_POWER_SUPPLY_OPEN
235 REXROTH_ERR_ES_DRIVE_ON_TIMEOUT
236 REXROTH_ERR_ES_DRIVE_OFF_TIMEOUT
237 REXROTH_ERR_ES_SMOKE_OR_FIRE_DETECTED
238 REXROTH_ERR_ES_ACTUAL_TORQUE_LIMIT_INVALID
239 REXROTH_ERR_ES_ABSOLUTE_ENCODER_NOT_IN_REFERENCE
250 REXROTH_ERR_ES_SOFTWARE_CRASHED
224 REXROTH_ERR_FB_FD_DRIVE_ERROR
240 REXROTH_ERR_FB_SERCOS_BUS
241 REXROTH_ERR_FB_SERCOS_SLAVE
255 REXROTH_ERR_EPO_LINE_FAILURE

MAVLink Commands (MAV_CMD)

MAVLink commands (MAV_CMD) and messages are different! These commands define the values of up to 7 parameters that are packaged INSIDE specific messages used in the Mission Protocol and Command Protocol. Use commands for actions in missions or if you need acknowledgment and/or retry logic from a request. Otherwise use messages.

MAVLink Messages

CONTROL_LOADING_AXIS ( #24401 )

WORK IN PROGRESS: Do not use in stable production environments (it may change).

[Message] (MAVLink 2) Send data about a control axis from a control loading system. This is the primary message for logging data from MARSH_COMP_ID_CONTROL_LOADING.

Field Name Type Units Values Description
time_boot_ms uint32_t ms Timestamp (time since system boot).
axis uint8_t CONTROL_AXIS Control axis on which the measurements were taken.
position float deg Axis position
velocity float deg/s Axis velocity
force float Force applied in the pilot in the direction of movement axis (not gripping force), measured at the position of pilot's third finger (ring). Unit N (Newton), currently not part of mavschema.xsd

MOTION_PLATFORM_STATE ( #24402 )

WORK IN PROGRESS: Do not use in stable production environments (it may change).

[Message] (MAVLink 2) State report for motion platform used for moving the cockpit with the pilot for motion cueing. This is the primary message for MARSH_COMP_ID_MOTION_PLATFORM

Field Name Type Units Values Description
time_boot_ms uint32_t ms Timestamp (time since system boot).
health uint8_t MOTION_PLATFORM_HEALTH Generic system health (error and warning) status.
mode uint8_t MOTION_PLATFORM_MODE Generic system operating mode.
x float m X axis (surge) position, positive forward.
y float m Y axis (sway) position, positive right.
z float m Z axis (heave) position, positive down.
pitch float rad Pitch position, positive nose up.
roll float rad Roll position, positive right.
yaw float rad Yaw position, positive right.
vel_x float m/s X axis (surge) velocity, positive forward.
vel_y float m/s Y axis (sway) velocity, positive right.
vel_z float m/s Z axis (heave) velocity, positive down.
vel_pitch float rad/s Pitch velocity, positive nose up.
vel_roll float rad/s Roll velocity, positive right.
vel_yaw float rad/s Yaw velocity, positive right.
acc_x float m/s/s X axis (surge) acceleration, positive forward.
acc_y float m/s/s Y axis (sway) acceleration, positive right.
acc_z float m/s/s Z axis (heave) acceleration, positive down.
acc_pitch float Pitch acceleration, positive nose up. Unit rad/s/s, currently not part of mavschema.xsd
acc_roll float Roll acceleration, positive right. Unit rad/s/s, currently not part of mavschema.xsd
acc_yaw float Yaw acceleration, positive right. Unit rad/s/s, currently not part of mavschema.xsd

REXROTH_MOTION_PLATFORM ( #24403 )

WORK IN PROGRESS: Do not use in stable production environments (it may change).

[Message] (MAVLink 2) State report specific for eMotion Motion System by Bosch Rexroth B.V. Values applicable to motion platforms in general are sent in MOTION_PLATFORM_STATE with the same timestamp. Actuators are numbered in a clockwise direction when looking from above, starting from the front right. Actuator position is 0 when actuator is in mid-stroke.

Field Name Type Units Values Description
time_boot_ms uint32_t ms Timestamp (time since system boot).
frame_count uint32_t Number of message as sent by the Motion System.
motion_status uint32_t Motion Status variable as sent by the system.
error_code uint8_t REXROTH_MOTION_PLATFORM_ERROR Error code extracted from motion status.
actuator1 float m Current actuator 1 position.
actuator2 float m Current actuator 2 position.
actuator3 float m Current actuator 3 position.
actuator4 float m Current actuator 4 position.
actuator5 float m Current actuator 5 position.
actuator6 float m Current actuator 6 position.
platform_setpoint_x float m X axis (surge) platform setpoint, positive forward.
platform_setpoint_y float m Y axis (sway) platform setpoint, positive right.
platform_setpoint_z float m Z axis (heave) platform setpoint, positive down.
platform_setpoint_pitch float rad Pitch platform setpoint, positive nose up.
platform_setpoint_roll float rad Roll platform setpoint, positive right.
platform_setpoint_yaw float rad Yaw platform setpoint, positive right.
effect_setpoint_x float m X axis (surge) special effect setpoint, positive forward.
effect_setpoint_y float m Y axis (sway) special effect setpoint, positive right.
effect_setpoint_z float m Z axis (heave) special effect setpoint, positive down.
effect_setpoint_pitch float rad Pitch special effect setpoint, positive nose up.
effect_setpoint_roll float rad Roll special effect setpoint, positive right.
effect_setpoint_yaw float rad Yaw special effect setpoint, positive right.

MOTION_CUE_EXTRA ( #24404 )

WORK IN PROGRESS: Do not use in stable production environments (it may change).

[Message] (MAVLink 2) These values are an extra cue that should be added to accelerations and rotations etc. resulting from aircraft state, with the resulting cue being the sum of the latest aircraft and extra values. An example use case would be a cockpit shaker.

Field Name Type Units Description
time_boot_ms uint32_t ms Timestamp (time since system boot).
vel_pitch float rad/s Pitch velocity, positive nose up.
vel_roll float rad/s Roll velocity, positive right.
vel_yaw float rad/s Yaw velocity, positive right.
acc_x float m/s/s X axis (surge) acceleration, positive forward.
acc_y float m/s/s Y axis (sway) acceleration, positive right.
acc_z float m/s/s Z axis (heave) acceleration, positive down.

EYE_TRACKING_DATA ( #24405 )

WORK IN PROGRESS: Do not use in stable production environments (it may change).

[Message] (MAVLink 2) Data for tracking of pilot eye gaze. In multi-crew situations, additional trackers should connect with different system id.

Field Name Type Units Description
time_usec uint64_t us Timestamp (time since system boot).
gaze_origin_x float m X axis of gaze origin point, NaN if unknown. The reference system depends on specific application.
gaze_origin_y float m Y axis of gaze origin point, NaN if unknown. The reference system depends on specific application.
gaze_origin_z float m Z axis of gaze origin point, NaN if unknown. The reference system depends on specific application.
gaze_direction_x float X axis of gaze direction vector, expected to be normalized to unit magnitude, NaN if unknown. The reference system should match origin point.
gaze_direction_y float Y axis of gaze direction vector, expected to be normalized to unit magnitude, NaN if unknown. The reference system should match origin point.
gaze_direction_z float Z axis of gaze direction vector, expected to be normalized to unit magnitude, NaN if unknown. The reference system should match origin point.
video_gaze_x float Gaze focal point on video feed x value (normalized 0..1, 0 is left, 1 is right), NaN if unknown
video_gaze_y float Gaze focal point on video feed y value (normalized 0..1, 0 is top, 1 is bottom), NaN if unknown
surface_id uint8_t Identifier of surface for 2D gaze point, or an identified region when surface point is invalid. Set to zero if unknown/unused.
surface_gaze_x float Gaze focal point on surface x value (normalized 0..1, 0 is left, 1 is right), NaN if unknown
surface_gaze_y float Gaze focal point on surface y value (normalized 0..1, 0 is top, 1 is bottom), NaN if unknown