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

Note

The ids of all messages have been changed in commit 3621719 on 2025-05-16 for inclusion in the upstream MAVLink repository. Custom messages saved in .tlog files before that change will not be recognised by newer code.

Definition list

Generated on 2025-05-28T08:58:00 from commit dd6420b

MAVLink Include Files: common.xml

This file has protocol dialect: 3.

MAVLink Type Enumerations

MARSH_TYPE

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

Value Field Name Description
100 MARSH_TYPE_MANAGER The simulation manager responsible for routing packets between different nodes. Typically MARSH Manager, see https://marsh-sim.github.io/manager.html
101 MARSH_TYPE_FLIGHT_MODEL Component simulating flight dynamics of the aircraft.
102 MARSH_TYPE_CONTROLS Component providing pilot control inputs.
103 MARSH_TYPE_VISUALISATION Component showing the visual situation to the pilot.
104 MARSH_TYPE_INSTRUMENTS Component implementing pilot instrument panel.
105 MARSH_TYPE_MOTION_PLATFORM Component that moves the entire cockpit for motion cueing.
106 MARSH_TYPE_GSEAT Component for in-seat motion cueing.
107 MARSH_TYPE_EYE_TRACKER Component providing gaze data of pilot eyes.
108 MARSH_TYPE_CONTROL_LOADING Component measuring and actuating forces on pilot control inputs.
109 MARSH_TYPE_VIBRATION_SOURCE Component providing vibrations for system identification, road rumble, gusts, etc.
110 MARSH_TYPE_PILOT_TARGET Component providing target for the pilot to follow like controls positions, aircraft state, ILS path etc.
111 MARSH_TYPE_EXPERIMENT_DIRECTOR Principal component controlling the main scenario of a given test, (unlike lower level MARSH_TYPE_PILOT_TARGET or MARSH_TYPE_MANAGER for overall communication).

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_ROLL Roll axis, with positive values corresponding to stick right movement, causing the vehicle to roll right. For helicopters this is lateral cyclic.
1 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.
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.

MARSH_MANUAL_SETPOINT_MODE

[Enum] Usage of MANUAL_SETPOINT message, sent in mode_switch field.

Value Field Name Description
0 MARSH_MANUAL_SETPOINT_MODE_TARGET Values for target inceptors positions that the pilot should follow.
1 MARSH_MANUAL_SETPOINT_MODE_TRIM Values for inceptors trim positions, the exact meaning depends on the flight model.

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.

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 ( #52501 )

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_TYPE_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 ( #52502 )

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_TYPE_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.
roll float rad Roll position, positive right.
pitch float rad Pitch position, positive nose up.
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_roll float rad/s Roll velocity, positive right.
vel_pitch float rad/s Pitch velocity, positive nose up.
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_roll float Roll acceleration, positive right. Unit rad/s/s, currently not part of mavschema.xsd
acc_pitch float Pitch acceleration, positive nose up. 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 ( #52503 )

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 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 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_roll float rad Roll platform setpoint, positive right.
platform_setpoint_pitch float rad Pitch platform setpoint, positive nose up.
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_roll float rad Roll special effect setpoint, positive right.
effect_setpoint_pitch float rad Pitch special effect setpoint, positive nose up.
effect_setpoint_yaw float rad Yaw special effect setpoint, positive right.

MOTION_CUE_EXTRA ( #52504 )

[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_roll float rad/s Roll velocity, positive right.
vel_pitch float rad/s Pitch velocity, positive nose up.
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 ( #52505 )

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

[Message] (MAVLink 2) Data for tracking of pilot eye gaze. This is the primary message for MARSH_TYPE_EYE_TRACKER.

Field Name Type Units Description
time_usec uint64_t us Timestamp (time since system boot).
sensor_id uint8_t Sensor ID, used for identifying the device and/or person tracked. Set to zero if unknown/unused.
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