Skip to content

Commit

Permalink
MAVLink: update
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed May 12, 2024
1 parent fb751eb commit 72bca87
Show file tree
Hide file tree
Showing 8 changed files with 53,650 additions and 53,009 deletions.
144 changes: 118 additions & 26 deletions ExtLibs/Mavlink/Mavlink.cs

Large diffs are not rendered by default.

105,682 changes: 53,058 additions & 52,624 deletions ExtLibs/Mavlink/mavlink.lua

Large diffs are not rendered by default.

6 changes: 6 additions & 0 deletions ExtLibs/Mavlink/message_definitions/ardupilotmega.xml
Original file line number Diff line number Diff line change
Expand Up @@ -423,6 +423,12 @@
<entry value="2" name="LAND_IMMEDIATELY">
<description>Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land.</description>
</entry>
<entry value="4" name="ALT_FRAME_VALID">
<description>True if the following altitude frame value is valid.</description>
</entry>
<entry value="24" name="ALT_FRAME">
<description>2 bit value representing altitude frame. 0: absolute, 1: relative home, 2: relative origin, 3: relative terrain</description>
</entry>
</enum>
<!-- Camera event types -->
<enum name="CAMERA_STATUS_TYPES">
Expand Down
135 changes: 122 additions & 13 deletions ExtLibs/Mavlink/message_definitions/common.xml

Large diffs are not rendered by default.

60 changes: 30 additions & 30 deletions ExtLibs/Mavlink/message_definitions/csAirLink.xml
Original file line number Diff line number Diff line change
@@ -1,30 +1,30 @@
<?xml version="1.0"?>
<mavlink>
<!-- ClearSky Air-Link contact info: -->
<!-- company URL: https://air-link.space/ -->
<!-- email contact: drone@air-link.space -->
<!-- mavlink ID range: 52000 - 52099 -->
<version>3</version>
<enums>
<enum name="AIRLINK_AUTH_RESPONSE_TYPE">
<entry value="0" name="AIRLINK_ERROR_LOGIN_OR_PASS">
<description>Login or password error</description>
</entry>
<entry value="1" name="AIRLINK_AUTH_OK">
<description>Auth successful</description>
</entry>
</enum>
</enums>
<messages>
<message id="52000" name="AIRLINK_AUTH">
<description>Authorization package</description>
<field type="char[50]" name="login">Login</field>
<field type="char[50]" name="password">Password</field>
</message>
<message id="52001" name="AIRLINK_AUTH_RESPONSE">
<description>Response to the authorization request</description>
<field type="uint8_t" name="resp_type" enum="AIRLINK_AUTH_RESPONSE_TYPE">Response type</field>
</message>
</messages>
</mavlink>

<?xml version="1.0"?>
<mavlink>
<!-- ClearSky Air-Link contact info: -->
<!-- company URL: https://air-link.space/ -->
<!-- email contact: drone@air-link.space -->
<!-- mavlink ID range: 52000 - 52099 -->
<version>3</version>
<enums>
<enum name="AIRLINK_AUTH_RESPONSE_TYPE">
<entry value="0" name="AIRLINK_ERROR_LOGIN_OR_PASS">
<description>Login or password error</description>
</entry>
<entry value="1" name="AIRLINK_AUTH_OK">
<description>Auth successful</description>
</entry>
</enum>
</enums>
<messages>
<message id="52000" name="AIRLINK_AUTH">
<description>Authorization package</description>
<field type="char[50]" name="login">Login</field>
<field type="char[50]" name="password">Password</field>
</message>
<message id="52001" name="AIRLINK_AUTH_RESPONSE">
<description>Response to the authorization request</description>
<field type="uint8_t" name="resp_type" enum="AIRLINK_AUTH_RESPONSE_TYPE">Response type</field>
</message>
</messages>
</mavlink>

98 changes: 49 additions & 49 deletions ExtLibs/Mavlink/message_definitions/cubepilot.xml
Original file line number Diff line number Diff line change
@@ -1,49 +1,49 @@
<?xml version="1.0"?>
<mavlink>
<!-- Cubepilot contact info: -->
<!-- company URL: http://www.cubepilot.com -->
<!-- email contact: siddharth@cubepilot.com or michael@cubepilot.com -->
<!-- mavlink ID range: 50000 - 50099 -->
<include>common.xml</include>
<messages>
<message id="50001" name="CUBEPILOT_RAW_RC">
<description>Raw RC Data</description>
<field type="uint8_t[32]" name="rc_raw"/>
</message>
<message id="50002" name="HERELINK_VIDEO_STREAM_INFORMATION">
<description>Information about video stream</description>
<field type="uint8_t" name="camera_id">Video Stream ID (1 for first, 2 for second, etc.)</field>
<field type="uint8_t" name="status">Number of streams available.</field>
<field type="float" name="framerate" units="Hz">Frame rate.</field>
<field type="uint16_t" name="resolution_h" units="pix">Horizontal resolution.</field>
<field type="uint16_t" name="resolution_v" units="pix">Vertical resolution.</field>
<field type="uint32_t" name="bitrate" units="bits/s">Bit rate.</field>
<field type="uint16_t" name="rotation" units="deg">Video image rotation clockwise.</field>
<field type="char[230]" name="uri">Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).</field>
</message>
<message id="50003" name="HERELINK_TELEM">
<description>Herelink Telemetry</description>
<field type="uint8_t" name="rssi"/>
<field type="int16_t" name="snr"/>
<field type="uint32_t" name="rf_freq"/>
<field type="uint32_t" name="link_bw"/>
<field type="uint32_t" name="link_rate"/>
<field type="int16_t" name="cpu_temp"/>
<field type="int16_t" name="board_temp"/>
</message>
<message id="50004" name="CUBEPILOT_FIRMWARE_UPDATE_START">
<description>Start firmware update with encapsulated data.</description>
<field type="uint8_t" name="target_system">System ID.</field>
<field type="uint8_t" name="target_component">Component ID.</field>
<field type="uint32_t" name="size" units="bytes">FW Size.</field>
<field type="uint32_t" name="crc">FW CRC.</field>
</message>
<message id="50005" name="CUBEPILOT_FIRMWARE_UPDATE_RESP">
<description>offset response to encapsulated data.</description>
<field type="uint8_t" name="target_system">System ID.</field>
<field type="uint8_t" name="target_component">Component ID.</field>
<field type="uint32_t" name="offset" units="bytes">FW Offset.</field>
</message>
</messages>
</mavlink>

<?xml version="1.0"?>
<mavlink>
<!-- Cubepilot contact info: -->
<!-- company URL: http://www.cubepilot.com -->
<!-- email contact: siddharth@cubepilot.com or michael@cubepilot.com -->
<!-- mavlink ID range: 50000 - 50099 -->
<include>common.xml</include>
<messages>
<message id="50001" name="CUBEPILOT_RAW_RC">
<description>Raw RC Data</description>
<field type="uint8_t[32]" name="rc_raw"/>
</message>
<message id="50002" name="HERELINK_VIDEO_STREAM_INFORMATION">
<description>Information about video stream</description>
<field type="uint8_t" name="camera_id">Video Stream ID (1 for first, 2 for second, etc.)</field>
<field type="uint8_t" name="status">Number of streams available.</field>
<field type="float" name="framerate" units="Hz">Frame rate.</field>
<field type="uint16_t" name="resolution_h" units="pix">Horizontal resolution.</field>
<field type="uint16_t" name="resolution_v" units="pix">Vertical resolution.</field>
<field type="uint32_t" name="bitrate" units="bits/s">Bit rate.</field>
<field type="uint16_t" name="rotation" units="deg">Video image rotation clockwise.</field>
<field type="char[230]" name="uri">Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).</field>
</message>
<message id="50003" name="HERELINK_TELEM">
<description>Herelink Telemetry</description>
<field type="uint8_t" name="rssi"/>
<field type="int16_t" name="snr"/>
<field type="uint32_t" name="rf_freq"/>
<field type="uint32_t" name="link_bw"/>
<field type="uint32_t" name="link_rate"/>
<field type="int16_t" name="cpu_temp"/>
<field type="int16_t" name="board_temp"/>
</message>
<message id="50004" name="CUBEPILOT_FIRMWARE_UPDATE_START">
<description>Start firmware update with encapsulated data.</description>
<field type="uint8_t" name="target_system">System ID.</field>
<field type="uint8_t" name="target_component">Component ID.</field>
<field type="uint32_t" name="size" units="bytes">FW Size.</field>
<field type="uint32_t" name="crc">FW CRC.</field>
</message>
<message id="50005" name="CUBEPILOT_FIRMWARE_UPDATE_RESP">
<description>offset response to encapsulated data.</description>
<field type="uint8_t" name="target_system">System ID.</field>
<field type="uint8_t" name="target_component">Component ID.</field>
<field type="uint32_t" name="offset" units="bytes">FW Offset.</field>
</message>
</messages>
</mavlink>

112 changes: 56 additions & 56 deletions ExtLibs/Mavlink/message_definitions/loweheiser.xml
Original file line number Diff line number Diff line change
@@ -1,56 +1,56 @@
<?xml version="1.0"?>
<mavlink>
<!-- Loweheiser contact info: -->
<!-- company URL: https://www.loweheiser.com/ -->
<!-- company LinkeIn: https://www.linkedin.com/company/loweheiser -->
<!-- email contact: info@loweheiser.com -->
<!-- mavlink ID range: 10150 - 10199 -->
<include>minimal.xml</include>
<enums>
<enum name="MAV_CMD">
<!-- Loweheiser specific MAV_CMD_* commands -->
<entry name="MAV_CMD_LOWEHEISER_SET_STATE" value="10151">
<description>Set Loweheiser desired states</description>
<param index="1">EFI Index</param>
<param index="2">Desired Engine/EFI State (0: Power Off, 1:Running)</param>
<param index="3">Desired Governor State (0:manual throttle, 1:Governed throttle)</param>
<param index="4">Manual throttle level, 0% - 100%</param>
<param index="5">Electronic Start up (0:Off, 1:On)</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
</enums>
<messages>
<message id="10151" name="LOWEHEISER_GOV_EFI">
<description>Composite EFI and Governor data from Loweheiser equipment. This message is created by the EFI unit based on its own data and data received from a governor attached to that EFI unit.</description>
<!-- Generator fields -->
<field type="float" name="volt_batt" units="V">Generator Battery voltage.</field>
<field type="float" name="curr_batt" units="A">Generator Battery current.</field>
<field type="float" name="curr_gen" units="A">Current being produced by generator.</field>
<field type="float" name="curr_rot" units="A">Load current being consumed by the UAV (sum of curr_gen and curr_batt)</field>
<field type="float" name="fuel_level" units="l">Generator fuel remaining in litres.</field>
<field type="float" name="throttle" units="%">Throttle Output.</field>
<field type="uint32_t" name="runtime" units="s">Seconds this generator has run since it was rebooted.</field>
<field type="int32_t" name="until_maintenance" units="s">Seconds until this generator requires maintenance. A negative value indicates maintenance is past due.</field>
<field type="float" name="rectifier_temp" units="degC">The Temperature of the rectifier.</field>
<field type="float" name="generator_temp" units="degC">The temperature of the mechanical motor, fuel cell core or generator.</field>
<!-- EFI fields -->
<field type="float" name="efi_batt" units="V"> EFI Supply Voltage.</field>
<field type="float" name="efi_rpm" units="rpm">Motor RPM.</field>
<field type="float" name="efi_pw" units="ms">Injector pulse-width in miliseconds.</field>
<field type="float" name="efi_fuel_flow">Fuel flow rate in litres/hour.</field>
<field type="float" name="efi_fuel_consumed" units="l">Fuel consumed.</field>
<field type="float" name="efi_baro" units="kPa">Atmospheric pressure.</field>
<field type="float" name="efi_mat" units="degC">Manifold Air Temperature.</field>
<field type="float" name="efi_clt" units="degC">Cylinder Head Temperature.</field>
<field type="float" name="efi_tps" units="%">Throttle Position.</field>
<field type="float" name="efi_exhaust_gas_temperature" units="degC">Exhaust gas temperature.</field>
<!-- Status fields -->
<field type="uint8_t" name="efi_index" instance="true">EFI index.</field>
<field type="uint16_t" name="generator_status">Generator status.</field>
<field type="uint16_t" name="efi_status">EFI status.</field>
</message>
</messages>
</mavlink>

<?xml version="1.0"?>
<mavlink>
<!-- Loweheiser contact info: -->
<!-- company URL: https://www.loweheiser.com/ -->
<!-- company LinkeIn: https://www.linkedin.com/company/loweheiser -->
<!-- email contact: info@loweheiser.com -->
<!-- mavlink ID range: 10150 - 10199 -->
<include>minimal.xml</include>
<enums>
<enum name="MAV_CMD">
<!-- Loweheiser specific MAV_CMD_* commands -->
<entry name="MAV_CMD_LOWEHEISER_SET_STATE" value="10151">
<description>Set Loweheiser desired states</description>
<param index="1">EFI Index</param>
<param index="2">Desired Engine/EFI State (0: Power Off, 1:Running)</param>
<param index="3">Desired Governor State (0:manual throttle, 1:Governed throttle)</param>
<param index="4">Manual throttle level, 0% - 100%</param>
<param index="5">Electronic Start up (0:Off, 1:On)</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
</enums>
<messages>
<message id="10151" name="LOWEHEISER_GOV_EFI">
<description>Composite EFI and Governor data from Loweheiser equipment. This message is created by the EFI unit based on its own data and data received from a governor attached to that EFI unit.</description>
<!-- Generator fields -->
<field type="float" name="volt_batt" units="V">Generator Battery voltage.</field>
<field type="float" name="curr_batt" units="A">Generator Battery current.</field>
<field type="float" name="curr_gen" units="A">Current being produced by generator.</field>
<field type="float" name="curr_rot" units="A">Load current being consumed by the UAV (sum of curr_gen and curr_batt)</field>
<field type="float" name="fuel_level" units="l">Generator fuel remaining in litres.</field>
<field type="float" name="throttle" units="%">Throttle Output.</field>
<field type="uint32_t" name="runtime" units="s">Seconds this generator has run since it was rebooted.</field>
<field type="int32_t" name="until_maintenance" units="s">Seconds until this generator requires maintenance. A negative value indicates maintenance is past due.</field>
<field type="float" name="rectifier_temp" units="degC">The Temperature of the rectifier.</field>
<field type="float" name="generator_temp" units="degC">The temperature of the mechanical motor, fuel cell core or generator.</field>
<!-- EFI fields -->
<field type="float" name="efi_batt" units="V"> EFI Supply Voltage.</field>
<field type="float" name="efi_rpm" units="rpm">Motor RPM.</field>
<field type="float" name="efi_pw" units="ms">Injector pulse-width in miliseconds.</field>
<field type="float" name="efi_fuel_flow">Fuel flow rate in litres/hour.</field>
<field type="float" name="efi_fuel_consumed" units="l">Fuel consumed.</field>
<field type="float" name="efi_baro" units="kPa">Atmospheric pressure.</field>
<field type="float" name="efi_mat" units="degC">Manifold Air Temperature.</field>
<field type="float" name="efi_clt" units="degC">Cylinder Head Temperature.</field>
<field type="float" name="efi_tps" units="%">Throttle Position.</field>
<field type="float" name="efi_exhaust_gas_temperature" units="degC">Exhaust gas temperature.</field>
<!-- Status fields -->
<field type="uint8_t" name="efi_index" instance="true">EFI index.</field>
<field type="uint16_t" name="generator_status">Generator status.</field>
<field type="uint16_t" name="efi_status">EFI status.</field>
</message>
</messages>
</mavlink>

Loading

0 comments on commit 72bca87

Please sign in to comment.