diff --git a/external/dialects/README.md b/external/dialects/README.md new file mode 100644 index 0000000000..a87eb796a0 --- /dev/null +++ b/external/dialects/README.md @@ -0,0 +1,30 @@ +## MAVLink External Dialects ## + +The [/external/dialects](https://github.com/mavlink/mavlink/tree/master/external/dialects) folder hosts MAVLink dialects of *external* projects; projects that are not maintained by core MAVLink stakeholders or part of the MAVLink standard. + +> **Note** This mechanism is provided to help non-stakeholder dialect owners avoid clashes with other dialects (and the standard), and to ease integration of generic behaviours into the standard in future. +> We recommend that you work with the standard rather than using this approach if at all possible (there are significant benefits in terms of compatibility and adoptability when using the standard definitions). + +Dialects XML files in this folder must meet the following criteria: + +* Comply with the [MAVLink XML file format](https://mavlink.io/en/guide/xml_schema.html) (confirm this by using mavgen to build the dialect with validation enabled). +* Metadata, in the form of separate comments near the top of the file, containing: + * Reliable contact information (email address strongly preferred). + * Ranges of the message IDs and command IDs that are reserved for the dialect. + > The range of message IDs and command IDs can be requested in the initial PR. + Message ids ranges should be above 60000, and are typically reserved in blocks of 50. + * (Optionally) Link to additional documentation (e.g. a web page) +* Include the dialect in [/mavlink/message_definitions/v1.0/all.xml](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/all.xml) along with a comment indicating the message/command ranges it uses (the "all" dialect is constantly tested and ensures that messsage IDs and command IDs do not conflict). + +You will generally be invited to attend the [Dev Call](https://mavlink.io/en/about/support.html#dev_call) (once) to gain final approval. +This is primarily for the MAVLink team to better understand your needs, and where the core standard can be improved. + +MAVlink reserves the right to refuse or remove a dialect that does not comply with the above conditions, or if required due for smooth running of the project (or some other common sense reason). + +Please inspect the dialects in this folder for guidance. + + +Links: +* [MAVLink XML File Schema / Format](https://mavlink.io/en/guide/xml_schema.html) +* [Dev Call](https://mavlink.io/en/about/support.html#dev_call) + diff --git a/external/dialects/storm32.xml b/external/dialects/storm32.xml new file mode 100644 index 0000000000..dd1feda372 --- /dev/null +++ b/external/dialects/storm32.xml @@ -0,0 +1,504 @@ + + + + + ../../message_definitions/v1.0/ardupilotmega.xml + 1 + 0 + + + + + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + + + + Gimbal device capability flags. + + Gimbal device supports a retracted position. + + + Gimbal device supports a horizontal, forward looking position, stabilized. Can also be used to reset the gimbal's orientation. + + + Gimbal device supports rotating around roll axis. + + + Gimbal device supports to follow a roll angle relative to the vehicle. + + + Gimbal device supports locking to an roll angle (generally that's the default). + + + Gimbal device supports rotating around pitch axis. + + + Gimbal device supports to follow a pitch angle relative to the vehicle. + + + Gimbal device supports locking to an pitch angle (generally that's the default). + + + Gimbal device supports rotating around yaw axis. + + + Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default). + + + Gimbal device supports locking to a heading angle. + + + Gimbal device supports yawing/panning infinitely (e.g. using a slip ring). + + + Gimbal device supports absolute yaw angles (this usually requires support by an autopilot, and can be dynamic, i.e., go on and off during runtime). + + + Gimbal device supports control via an RC input signal. + + + + + Flags for gimbal device operation. Used for setting and reporting, unless specified otherwise. Settings which are in violation of the capability flags are ignored by the gimbal device. + + Retracted safe position (no stabilization), takes presedence over NEUTRAL flag. If supported by the gimbal, the angles in the retracted position can be set in addition. + + + Neutral position (horizontal, forward looking, with stabiliziation). + + + Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default. + + + Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default. + + + Lock yaw angle to absolute angle relative to earth (not relative to drone). When the YAW_ABSOLUTE flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). + + + Gimbal device can accept absolute yaw angle input. This flag cannot be set, is only for reporting (attempts to set it are rejected by the gimbal device). + + + Yaw angle is absolute (is only accepted if CAN_ACCEPT_YAW_ABSOLUTE is set). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). + + + RC control. The RC input signal fed to the gimbal device exclusively controls the gimbal's orientation. Overrides RC_MIXED flag if that is also set. + + + RC control. The RC input signal fed to the gimbal device is mixed into the gimbal's orientation. Is overriden by RC_EXCLUSIVE flag if that is also set. + + + UINT16_MAX = ignore. + + + + + Gimbal device error and condition flags (0 means no error or other condition). + + Gimbal device is limited by hardware roll limit. + + + Gimbal device is limited by hardware pitch limit. + + + Gimbal device is limited by hardware yaw limit. + + + There is an error with the gimbal device's encoders. + + + There is an error with the gimbal device's power source. + + + There is an error with the gimbal device's motors. + + + There is an error with the gimbal device's software. + + + There is an error with the gimbal device's communication. + + + Gimbal device is currently calibrating (not an error). + + + Gimbal device is not assigned to a gimbal manager (not an error). + + + + + + Gimbal manager capability flags. + + The gimbal manager supports several profiles. + + + The gimbal manager supports changing the gimbal manager during run time, i.e. can be enabled/disabled. + + + + + Flags for gimbal manager operation. Used for setting and reporting, unless specified otherwise. If a setting is accepted by the gimbal manger, is reported in the STORM32_GIMBAL_MANAGER_STATUS message. + + 0 = ignore. + + + Request to set RC input to active, or report RC input is active. Implies RC mixed. RC exclusive is achieved by setting all clients to inactive. + + + Request to set onboard/companion computer client to active, or report this client is active. + + + Request to set autopliot client to active, or report this client is active. + + + Request to set GCS client to active, or report this client is active. + + + Request to set camera client to active, or report this client is active. + + + Request to set GCS2 client to active, or report this client is active. + + + Request to set camera2 client to active, or report this client is active. + + + Request to set custom client to active, or report this client is active. + + + Request to set custom2 client to active, or report this client is active. + + + Request supervision. This flag is only for setting, it is not reported. + + + Release supervision. This flag is only for setting, it is not reported. + + + + + Gimbal manager client ID. In a prioritizing profile, the priorities are determined by the implementation; they could e.g. be custom1 > onboard > GCS > autopilot/camera > GCS2 > custom2. + + For convenience. + + + This is the onboard/companion computer client. + + + This is the autopilot client. + + + This is the GCS client. + + + This is the camera client. + + + This is the GCS2 client. + + + This is the camera2 client. + + + This is the custom client. + + + This is the custom2 client. + + + + + Flags for gimbal manager set up. Used for setting and reporting, unless specified otherwise. + + Enable gimbal manager. This flag is only for setting, is not reported. + + + Disable gimbal manager. This flag is only for setting, is not reported. + + + + + Gimbal manager profiles. Only standard profiles are defined. Any implementation can define it's own profile in addition, and should use enum values > 16. + + Default profile. Implementation specific. + + + Custom profile. Configurable profile according to the STorM32 definition. Is configured with STORM32_GIMBAL_MANAGER_PROFIL. + + + Default cooperative profile. Uses STorM32 custom profile with default settings to achieve cooperative behavior. + + + Default exclusive profile. Uses STorM32 custom profile with default settings to achieve exclusive behavior. + + + Default priority profile with cooperative behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior. + + + Default priority profile with exclusive behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior. + + + + + Gimbal actions. + + Trigger the gimbal device to recenter the gimbal. + + + Trigger the gimbal device to run a calibration. + + + Trigger gimbal device to (re)discover the gimbal manager during run time. + + + + + + Enumeration of possible shot modes. + + Undefined shot mode. Can be used to determine if qshots should be used or not. + + + Start normal gimbal operation. Is usally used to return back from a shot. + + + Load and keep safe gimbal position and stop stabilization. + + + Load neutral gimbal position and keep it while stabilizing. + + + Start mission with gimbal control. + + + Start RC gimbal control. + + + Start gimbal tracking the point specified by Lat, Lon, Alt. + + + Start gimbal tracking the system with specified system ID. + + + Start 2-point cable cam quick shot. + + + + + + + + + Command to a gimbal manager to control the gimbal tilt and pan angles. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. A gimbal device is never to react to this command. + Pitch/tilt angle (positive: tilt up, NaN to be ignored). + Yaw/pan angle (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + Pitch/tilt rate (positive: tilt up, NaN to be ignored). + Yaw/pan rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + Gimbal device flags. + Gimbal manager flags. + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). The client is copied into bits 8-15. + + + + + Command to configure a gimbal manager. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. + Gimbal manager profile (0 = default). + Gimbal manager setup flags (0 = none). + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. + + + + + Command to initiate gimbal actions. Usually performed by the gimbal device, but some can also be done by the gimbal manager. It is hence best to broadcast this command. + Gimbal action to initiate (0 = none). + Gimbal ID of the gimbal to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. + + + + + Command to set the shot manager mode. + Set shot mode. + Set shot state or command. The allowed values are specific to the selected shot mode. + + + + + + + + + + Message reporting the current status of a gimbal device. This message should be broadcasted by a gimbal device component at a low regular rate (e.g. 4 Hz). For higher rates it should be emitted with a target. + System ID + Component ID + Timestamp (time since system boot). + Gimbal device flags currently applied. + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag. + X component of angular velocity (NaN if unknown). + Y component of angular velocity (NaN if unknown). + Z component of angular velocity (the frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN if unknown). + Yaw in absolute frame relative to Earth's North, north is 0 (NaN if unknown). + Failure flags (0 for no failure). + + + + Message to a gimbal device to control its attitude. This message is to be sent from the gimbal manager to the gimbal device. Angles and rates can be set to NaN according to use case. + System ID + Component ID + Gimbal device flags (UINT16_MAX to be ignored). + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + X component of angular velocity (positive: roll to the right, NaN to be ignored). + Y component of angular velocity (positive: tilt up, NaN to be ignored). + Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + + + + + Information about a gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. It mirrors some fields of the STORM32_GIMBAL_DEVICE_INFORMATION message, but not all. If the additional information is desired, also STORM32_GIMBAL_DEVICE_INFORMATION should be requested. + Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for. + Gimbal device capability flags. + Gimbal manager capability flags. + Hardware minimum roll angle (positive: roll to the right, NaN if unknown). + Hardware maximum roll angle (positive: roll to the right, NaN if unknown). + Hardware minimum pitch/tilt angle (positive: tilt up, NaN if unknown). + Hardware maximum pitch/tilt angle (positive: tilt up, NaN if unknown). + Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown). + Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown). + + + + Message reporting the current status of a gimbal manager. This message should be broadcast at a low regular rate (e.g. 1 Hz, may be increase momentarily to e.g. 5 Hz for a period of 1 sec after a change). + Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for. + Client who is currently supervisor (0 = none). + Gimbal device flags currently applied. + Gimbal manager flags currently applied. + Profile currently applied (0 = default). + + + + Message to a gimbal manager to control the gimbal attitude. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message. + System ID + Component ID + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + Client which is contacting the gimbal manager (must be set). + Gimbal device flags (UINT16_MAX to be ignored). + Gimbal manager flags (0 to be ignored). + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the GIMBAL_MANAGER_FLAGS_ABSOLUTE_YAW flag, NaN to be ignored). + X component of angular velocity (positive: roll to the right, NaN to be ignored). + Y component of angular velocity (positive: tilt up, NaN to be ignored). + Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + + + + Message to a gimbal manager to control the gimbal tilt and pan angles. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message. + System ID + Component ID + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + Client which is contacting the gimbal manager (must be set). + Gimbal device flags (UINT16_MAX to be ignored). + Gimbal manager flags (0 to be ignored). + Pitch/tilt angle (positive: tilt up, NaN to be ignored). + Yaw/pan angle (positive: pan the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + Pitch/tilt angular rate (positive: tilt up, NaN to be ignored). + Yaw/pan angular rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + + + + Message to a gimbal manager to correct the gimbal roll angle. This message is typically used to manually correct for a tilted horizon in operation. A gimbal device is never to react to this message. + System ID + Component ID + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + Client which is contacting the gimbal manager (must be set). + Roll angle (positive to roll to the right). + + + + + Message to set a gimbal manager profile. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. + System ID + Component ID + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + Profile to be applied (0 = default). + Priorities for custom profile. + Profile flags for custom profile (0 = default). + Rc timeouts for custom profile (0 = infinite, in uints of 100 ms). + Timeouts for custom profile (0 = infinite, in uints of 100 ms). + + + + + + Information about the shot operation. + Current shot mode. + Current state in the shot. States are specific to the selected shot mode. + + + diff --git a/message_definitions/v1.0/all.xml b/message_definitions/v1.0/all.xml index 1365cbcfb6..5634144e56 100644 --- a/message_definitions/v1.0/all.xml +++ b/message_definitions/v1.0/all.xml @@ -17,5 +17,11 @@ test.xml ualberta.xml uAvionix.xml + + + ../../external/dialects/storm32.xml