Skip to content

Commit

Permalink
further updates 3
Browse files Browse the repository at this point in the history
  • Loading branch information
jlpoltrack authored and peterbarker committed Feb 27, 2024
1 parent 78d4176 commit f1ff3e7
Showing 1 changed file with 82 additions and 82 deletions.
164 changes: 82 additions & 82 deletions message_definitions/v1.0/development.xml
Original file line number Diff line number Diff line change
@@ -1,82 +1,82 @@
<?xml version="1.0"?>
<mavlink>
<!-- XML file for prototyping definitions for standard.xml -->
<include>standard.xml</include>
<version>0</version>
<dialect>0</dialect>
<enums>
<enum name="AIRSPEED_SENSOR_FLAGS" bitmask="true">
<description>Airspeed sensor flags</description>
<entry value="0" name="AIRSPEED_SENSOR_UNHEALTHY">
<description>Airspeed sensor is unhealthy</description>
</entry>
<entry value="1" name="AIRSPEED_SENSOR_USING">
<description>True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control.</description>
</entry>
</enum>
<enum name="RADIO_RC_CHANNELS_FLAGS" bitmask="true">
<description>RADIO_RC_CHANNELS flags (bitmask).</description>
<entry value="1" name="RADIO_RC_CHANNELS_FLAGS_FAILSAFE">
<description>Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent.</description>
</entry>
<entry value="2" name="RADIO_RC_CHANNELS_FLAGS_OUTDATED">
<description>Content of the RC channels field in the RADIO_RC_CHANNELS message does not contain the current/latest RC data but the last RC data received.</description>
</entry>
</enum>
</enums>
<messages>
<message id="53" name="MISSION_CHECKSUM">
<description>Checksum for the current mission, rally point or geofence plan, or for the "combined" plan (a GCS can use these checksums to determine if it has matching plans).
This message must be broadcast with the appropriate checksum following any change to a mission, geofence or rally point definition
(immediately after the MISSION_ACK that completes the upload sequence).
It may also be requested using MAV_CMD_REQUEST_MESSAGE, where param 2 indicates the plan type for which the checksum is required.
The checksum must be calculated on the autopilot, but may also be calculated by the GCS.
The checksum uses the same CRC32 algorithm as MAVLink FTP (https://mavlink.io/en/services/ftp.html#crc32-implementation).
The checksum for a mission, geofence or rally point definition is run over each item in the plan in seq order (excluding the home location if present in the plan), and covers the following fields (in order):
frame, command, autocontinue, param1, param2, param3, param4, param5, param6, param7.
The checksum for the whole plan (MAV_MISSION_TYPE_ALL) is calculated using the same approach, running over each sub-plan in the following order: mission, geofence then rally point.
</description>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type.</field>
<field type="uint32_t" name="checksum">CRC32 checksum of current plan for specified type.</field>
</message>
<message id="295" name="AIRSPEED">
<description>Airspeed information from a sensor.</description>
<field type="uint8_t" name="id" instance="true">Sensor ID.</field>
<field type="float" name="airspeed" units="m/s">Calibrated airspeed (CAS).</field>
<field type="int16_t" name="temperature" units="cdegC">Temperature. INT16_MAX for value unknown/not supplied.</field>
<field type="float" name="raw_press" units="hPa">Raw differential pressure. NaN for value unknown/not supplied.</field>
<field type="uint8_t" name="flags" enum="AIRSPEED_SENSOR_FLAGS">Airspeed sensor flags.</field>
</message>
<message id="420" name="RADIO_RC_CHANNELS">
<description>RC channel outputs from a MAVLink RC receiver for input to a flight controller or other components
(allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS).
Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar
messages reported by the flight controller. The target_system field should normally be set to the system id of
the system to control, typically the flight controller. The target_component field can normally be set to 0, so
that all components of the system can receive the message.
The channels array field can publish up to 32 channels; the number of channel items used in the array is
specified in the count field.
The time_last_update_ms field contains the timestamp of the last received valid channels data in the
receiver's time domain, and the channel items up to count holds the last valid data.
If the channels data are not up-to-date and do not hold the current/latest data, the RADIO_RC_CHANNELS_FLAGS_OUTDATED
flag is set by the receiver.
The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver's failsafe condition
is met (implementation dependent, e.g., connection to the RC radio is lost). In this case time_last_update_ms
still contains the timestamp of the last valid channels data, but the content of the channels data is not
defined by the protocol but is up to the implementation of the receiver. For instance, the channels data could
contain failsafe values configured in the receiver; the default is to carry the last valid data.
Note: The RC channels fields are extensions to ensure that they are located at the end of the serialized payload
and subject to MAVLink's trailing-zero trimming.
</description>
<field type="uint8_t" name="target_system">System ID (ID of target system, normally flight controller).</field>
<field type="uint8_t" name="target_component">Component ID (normally 0 for broadcast).</field>
<field type="uint32_t" name="time_last_update_ms" units="ms">Time when the data in the channels field were last updated (time since boot in the receiver's time domain).</field>
<field type="uint16_t" name="flags" enum="RADIO_RC_CHANNELS_FLAGS" display="bitmask">Radio RC channels status flags.</field>
<field type="uint8_t" name="count">Total number of RC channels being received. This can be larger than 32, indicating that more channels are available but not given in this message.</field>
<extensions/>
<field type="int16_t[32]" name="channels" minValue="-4096" maxValue="4096">RC channels.
Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500.
Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming.</field>
</message>
</messages>
</mavlink>
<?xml version="1.0"?>
<mavlink>
<!-- XML file for prototyping definitions for standard.xml -->
<include>standard.xml</include>
<version>0</version>
<dialect>0</dialect>
<enums>
<enum name="AIRSPEED_SENSOR_FLAGS" bitmask="true">
<description>Airspeed sensor flags</description>
<entry value="0" name="AIRSPEED_SENSOR_UNHEALTHY">
<description>Airspeed sensor is unhealthy</description>
</entry>
<entry value="1" name="AIRSPEED_SENSOR_USING">
<description>True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control.</description>
</entry>
</enum>
<enum name="RADIO_RC_CHANNELS_FLAGS" bitmask="true">
<description>RADIO_RC_CHANNELS flags (bitmask).</description>
<entry value="1" name="RADIO_RC_CHANNELS_FLAGS_FAILSAFE">
<description>Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent.</description>
</entry>
<entry value="2" name="RADIO_RC_CHANNELS_FLAGS_OUTDATED">
<description>Content of the RC channels field in the RADIO_RC_CHANNELS message does not contain the current/latest RC data but the last RC data received.</description>
</entry>
</enum>
</enums>
<messages>
<message id="53" name="MISSION_CHECKSUM">
<description>Checksum for the current mission, rally point or geofence plan, or for the "combined" plan (a GCS can use these checksums to determine if it has matching plans).
This message must be broadcast with the appropriate checksum following any change to a mission, geofence or rally point definition
(immediately after the MISSION_ACK that completes the upload sequence).
It may also be requested using MAV_CMD_REQUEST_MESSAGE, where param 2 indicates the plan type for which the checksum is required.
The checksum must be calculated on the autopilot, but may also be calculated by the GCS.
The checksum uses the same CRC32 algorithm as MAVLink FTP (https://mavlink.io/en/services/ftp.html#crc32-implementation).
The checksum for a mission, geofence or rally point definition is run over each item in the plan in seq order (excluding the home location if present in the plan), and covers the following fields (in order):
frame, command, autocontinue, param1, param2, param3, param4, param5, param6, param7.
The checksum for the whole plan (MAV_MISSION_TYPE_ALL) is calculated using the same approach, running over each sub-plan in the following order: mission, geofence then rally point.
</description>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type.</field>
<field type="uint32_t" name="checksum">CRC32 checksum of current plan for specified type.</field>
</message>
<message id="295" name="AIRSPEED">
<description>Airspeed information from a sensor.</description>
<field type="uint8_t" name="id" instance="true">Sensor ID.</field>
<field type="float" name="airspeed" units="m/s">Calibrated airspeed (CAS).</field>
<field type="int16_t" name="temperature" units="cdegC">Temperature. INT16_MAX for value unknown/not supplied.</field>
<field type="float" name="raw_press" units="hPa">Raw differential pressure. NaN for value unknown/not supplied.</field>
<field type="uint8_t" name="flags" enum="AIRSPEED_SENSOR_FLAGS">Airspeed sensor flags.</field>
</message>
<message id="420" name="RADIO_RC_CHANNELS">
<description>RC channel outputs from a MAVLink RC receiver for input to a flight controller or other components
(allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS).
Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar
messages reported by the flight controller. The target_system field should normally be set to the system id of
the system to control, typically the flight controller. The target_component field can normally be set to 0, so
that all components of the system can receive the message.
The channels array field can publish up to 32 channels; the number of channel items used in the array is
specified in the count field.
The time_last_update_ms field contains the timestamp of the last received valid channels data in the
receiver's time domain, and the channel items up to count holds the last valid data.
If the channels data are not up-to-date and do not hold the current/latest data, the RADIO_RC_CHANNELS_FLAGS_OUTDATED
flag is set by the receiver.
The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver's failsafe condition
is met (implementation dependent, e.g., connection to the RC radio is lost). In this case time_last_update_ms
still contains the timestamp of the last valid channels data, but the content of the channels data is not
defined by the protocol but is up to the implementation of the receiver. For instance, the channels data could
contain failsafe values configured in the receiver; the default is to carry the last valid data.
Note: The RC channels fields are extensions to ensure that they are located at the end of the serialized payload
and subject to MAVLink's trailing-zero trimming.
</description>
<field type="uint8_t" name="target_system">System ID (ID of target system, normally flight controller).</field>
<field type="uint8_t" name="target_component">Component ID (normally 0 for broadcast).</field>
<field type="uint32_t" name="time_last_update_ms" units="ms">Time when the data in the channels field were last updated (time since boot in the receiver's time domain).</field>
<field type="uint16_t" name="flags" enum="RADIO_RC_CHANNELS_FLAGS" display="bitmask">Radio RC channels status flags.</field>
<field type="uint8_t" name="count">Total number of RC channels being received. This can be larger than 32, indicating that more channels are available but not given in this message.</field>
<extensions/>
<field type="int16_t[32]" name="channels" minValue="-4096" maxValue="4096">RC channels.
Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500.
Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming.</field>
</message>
</messages>
</mavlink>

0 comments on commit f1ff3e7

Please sign in to comment.