From 8865e68d0f9b4e59b4107c124a201444ecfe41db Mon Sep 17 00:00:00 2001 From: JLP Date: Wed, 6 Dec 2023 07:56:48 -0500 Subject: [PATCH 01/10] development.xml: RADIO_RC_CHANNELS message --- message_definitions/v1.0/development.xml | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index dbe60ab8b3..a998d65417 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -14,6 +14,15 @@ True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. + + RADIO_RC_CHANNELS flags (bitmask). + + Failsafe is active. + + + Indicates that the current frame has not been received. Channel values are frozen. + + @@ -38,5 +47,15 @@ Raw differential pressure. NaN for value unknown/not supplied. Airspeed sensor flags. + + Radio channels. Supports up to 32 channels. Channel values are in centered 13 bit format. Range is [-4096,4096], center is 0. Conversion to PWM is x * 5/32 + 1500. + Should be emitted only by components with component id MAV_COMP_ID_TELEMETRY_RADIO. + The message should be handled, e.g. by routers, as if it had target fields with target_system = system id of system the radio receiver is connected to and target_component = 0. + + Total number of RC channels being received. This can be larger than 24, indicating that more channels are available but not given in this message. + Radio rc channels status flags. + + RC channels. Channels above count should be set to 0, to benefit from MAVLink's zero padding. + From ad21308ac55aef73ba7e642d2058a7d5a8d3f5ad Mon Sep 17 00:00:00 2001 From: JLP Date: Thu, 28 Dec 2023 10:14:00 -0500 Subject: [PATCH 02/10] add target fields --- message_definitions/v1.0/development.xml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index a998d65417..680bb32c9e 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -48,10 +48,11 @@ Airspeed sensor flags. - Radio channels. Supports up to 32 channels. Channel values are in centered 13 bit format. Range is [-4096,4096], center is 0. Conversion to PWM is x * 5/32 + 1500. - Should be emitted only by components with component id MAV_COMP_ID_TELEMETRY_RADIO. - The message should be handled, e.g. by routers, as if it had target fields with target_system = system id of system the radio receiver is connected to and target_component = 0. + Radio channels. Supports up to 32 channels. Channel values are in centered 13 bit format. Range is [-4096,4096], center is 0. Conversion to PWM is x * 5/32 + 1500. + The target_system field should normally be set to the system id of system the radio receiver is connected to, the target_component field can be normally set to 0. + System ID (can be 0 for broadcast, but this is discouraged). + Component ID (normally 0 for broadcast). Total number of RC channels being received. This can be larger than 24, indicating that more channels are available but not given in this message. Radio rc channels status flags. From 5a59ee3c7e4cfbe126ed48d1ff4dd88a017fb09e Mon Sep 17 00:00:00 2001 From: JLP Date: Fri, 26 Jan 2024 07:10:57 -0500 Subject: [PATCH 03/10] address feedback --- message_definitions/v1.0/development.xml | 24 +++++++++++++++--------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 680bb32c9e..224c6b290e 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -19,9 +19,6 @@ Failsafe is active. - - Indicates that the current frame has not been received. Channel values are frozen. - @@ -48,15 +45,24 @@ Airspeed sensor flags. - Radio channels. Supports up to 32 channels. Channel values are in centered 13 bit format. Range is [-4096,4096], center is 0. Conversion to PWM is x * 5/32 + 1500. - The target_system field should normally be set to the system id of system the radio receiver is connected to, the target_component field can be normally set to 0. - + RC channel inputs for a flight controller and associated components; the message does not replace the RC_CHANNELS and similar output messages. + Supports up to 32 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. + 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 time_last_update_ms field indicates the time, in the sender's time domain, when the RC channels data were last updated. If this time is significantly shorter + than the expected update time for this message, then the RC channels data can be considered invalid, and the RC channels data should carry the last valid data. + In the case of a failsafe (when the RADIO_RC_CHANNELS_FLAGS_FAILSAFE bit set in the flags field), the RC channels data can be frozen and carried forward, e.g., + the last valid data or failsafe values configured in the sender of the message. The exact behavior is not defined by the protocol but up to the implementation + of the sender; 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. + System ID (can be 0 for broadcast, but this is discouraged). Component ID (normally 0 for broadcast). - Total number of RC channels being received. This can be larger than 24, indicating that more channels are available but not given in this message. - Radio rc channels status flags. + Time when RC channels were last updated (time since boot in the sender's time domain). + Radio RC channels status flags. + 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. - RC channels. Channels above count should be set to 0, to benefit from MAVLink's zero padding. + RC channels. Channels that are above the field count should be set to 0, to benefit from MAVLink's trailing-zero trimming. From 4cb1e2b0591f5476c9a760f6017e8e444562fa5f Mon Sep 17 00:00:00 2001 From: JLP Date: Wed, 14 Feb 2024 08:08:12 -0500 Subject: [PATCH 04/10] further updates --- message_definitions/v1.0/development.xml | 150 +++++++++++++---------- 1 file changed, 82 insertions(+), 68 deletions(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 224c6b290e..c08eac776c 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -1,68 +1,82 @@ - - - - standard.xml - 0 - 0 - - - Airspeed sensor flags - - Airspeed sensor is unhealthy - - - True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. - - - - RADIO_RC_CHANNELS flags (bitmask). - - Failsafe is active. - - - - - - 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. - - Mission type. - CRC32 checksum of current plan for specified type. - - - Airspeed information from a sensor. - Sensor ID. - Calibrated airspeed (CAS). - Temperature. INT16_MAX for value unknown/not supplied. - Raw differential pressure. NaN for value unknown/not supplied. - Airspeed sensor flags. - - - RC channel inputs for a flight controller and associated components; the message does not replace the RC_CHANNELS and similar output messages. - Supports up to 32 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. - 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 time_last_update_ms field indicates the time, in the sender's time domain, when the RC channels data were last updated. If this time is significantly shorter - than the expected update time for this message, then the RC channels data can be considered invalid, and the RC channels data should carry the last valid data. - In the case of a failsafe (when the RADIO_RC_CHANNELS_FLAGS_FAILSAFE bit set in the flags field), the RC channels data can be frozen and carried forward, e.g., - the last valid data or failsafe values configured in the sender of the message. The exact behavior is not defined by the protocol but up to the implementation - of the sender; 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. - - System ID (can be 0 for broadcast, but this is discouraged). - Component ID (normally 0 for broadcast). - Time when RC channels were last updated (time since boot in the sender's time domain). - Radio RC channels status flags. - 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. - - RC channels. Channels that are above the field count should be set to 0, to benefit from MAVLink's trailing-zero trimming. - - - + + + + standard.xml + 0 + 0 + + + Airspeed sensor flags + + Airspeed sensor is unhealthy + + + True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. + + + + RADIO_RC_CHANNELS flags (bitmask). + + Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent. + + + 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. + + + + + + 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. + + Mission type. + CRC32 checksum of current plan for specified type. + + + Airspeed information from a sensor. + Sensor ID. + Calibrated airspeed (CAS). + Temperature. INT16_MAX for value unknown/not supplied. + Raw differential pressure. NaN for value unknown/not supplied. + Airspeed sensor flags. + + + 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. + + System ID (ID of target system, normally flight controller). + Component ID (normally 0 for broadcast). + Time when the data in the channels field were last updated (time since boot in the receiver's time domain). + Radio RC channels status flags. + 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. + + 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. + + + From 5d5cea1f6d650428b339a2d31ce12db82e8250f9 Mon Sep 17 00:00:00 2001 From: JLP Date: Wed, 14 Feb 2024 08:23:39 -0500 Subject: [PATCH 05/10] further updates 2 --- message_definitions/v1.0/development.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index c08eac776c..93cbc5460b 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -79,4 +79,4 @@ Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming. - + \ No newline at end of file From 7d96b50944a5169510c4f6824b09be4439fb9b6d Mon Sep 17 00:00:00 2001 From: JLP Date: Wed, 14 Feb 2024 08:40:25 -0500 Subject: [PATCH 06/10] further updates 3 --- message_definitions/v1.0/development.xml | 164 +++++++++++------------ 1 file changed, 82 insertions(+), 82 deletions(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 93cbc5460b..174936d3bd 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -1,82 +1,82 @@ - - - - standard.xml - 0 - 0 - - - Airspeed sensor flags - - Airspeed sensor is unhealthy - - - True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. - - - - RADIO_RC_CHANNELS flags (bitmask). - - Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent. - - - 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. - - - - - - 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. - - Mission type. - CRC32 checksum of current plan for specified type. - - - Airspeed information from a sensor. - Sensor ID. - Calibrated airspeed (CAS). - Temperature. INT16_MAX for value unknown/not supplied. - Raw differential pressure. NaN for value unknown/not supplied. - Airspeed sensor flags. - - - 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. - - System ID (ID of target system, normally flight controller). - Component ID (normally 0 for broadcast). - Time when the data in the channels field were last updated (time since boot in the receiver's time domain). - Radio RC channels status flags. - 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. - - 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. - - - \ No newline at end of file + + + + standard.xml + 0 + 0 + + + Airspeed sensor flags + + Airspeed sensor is unhealthy + + + True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. + + + + RADIO_RC_CHANNELS flags (bitmask). + + Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent. + + + 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. + + + + + + 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. + + Mission type. + CRC32 checksum of current plan for specified type. + + + Airspeed information from a sensor. + Sensor ID. + Calibrated airspeed (CAS). + Temperature. INT16_MAX for value unknown/not supplied. + Raw differential pressure. NaN for value unknown/not supplied. + Airspeed sensor flags. + + + 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. + + System ID (ID of target system, normally flight controller). + Component ID (normally 0 for broadcast). + Time when the data in the channels field were last updated (time since boot in the receiver's time domain). + Radio RC channels status flags. + 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. + + 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. + + + From 88cdc26b618ba3d28d5c62b69c492f68667a3e5d Mon Sep 17 00:00:00 2001 From: JLP Date: Thu, 15 Feb 2024 06:51:39 -0500 Subject: [PATCH 07/10] further updates 4 --- message_definitions/v1.0/development.xml | 33 ++++++++++-------------- 1 file changed, 13 insertions(+), 20 deletions(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 174936d3bd..b23eccaa22 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -20,7 +20,7 @@ Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent. - 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. + Channel data may be out of date. This is set when the receiver is unable to parse incoming data from the transmitter and has therefore resent the last data it was able to process. @@ -48,25 +48,18 @@ Airspeed sensor flags. - 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. + 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. + The count field indicates the first index of the channel array that holds invalid data. + The RADIO_RC_CHANNELS_FLAGS_OUTDATED flag is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be decoded so the previous data is resent). + 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 (it 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. System ID (ID of target system, normally flight controller). Component ID (normally 0 for broadcast). From 9e0907d25b9f71c431ea3fe582cbaace329f06ae Mon Sep 17 00:00:00 2001 From: jlpoltrack <41841496+jlpoltrack@users.noreply.github.com> Date: Wed, 21 Feb 2024 06:24:50 -0500 Subject: [PATCH 08/10] Update message_definitions/v1.0/development.xml Co-authored-by: Hamish Willee --- message_definitions/v1.0/development.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index b23eccaa22..eabc3b01cc 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -20,7 +20,7 @@ Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent. - Channel data may be out of date. This is set when the receiver is unable to parse incoming data from the transmitter and has therefore resent the last data it was able to process. + Channel data may be out of date. This is set when the receiver is unable to validate incoming data from the transmitter and has therefore resent the last valid data it received. From af01ec55ddca714f0d5b52dc88f43b700900ce15 Mon Sep 17 00:00:00 2001 From: jlpoltrack <41841496+jlpoltrack@users.noreply.github.com> Date: Wed, 21 Feb 2024 06:25:10 -0500 Subject: [PATCH 09/10] Update message_definitions/v1.0/development.xml Co-authored-by: Hamish Willee --- message_definitions/v1.0/development.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index eabc3b01cc..63777e8876 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -55,7 +55,7 @@ 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. The count field indicates the first index of the channel array that holds invalid data. - The RADIO_RC_CHANNELS_FLAGS_OUTDATED flag is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be decoded so the previous data is resent). + The RADIO_RC_CHANNELS_FLAGS_OUTDATED flag is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be validated so the last valid data is resent). 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 (it 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. From 0dc3b40bc779f7e1c8f535fa004ce3726329aa29 Mon Sep 17 00:00:00 2001 From: jlpoltrack <41841496+jlpoltrack@users.noreply.github.com> Date: Wed, 21 Feb 2024 20:06:14 -0500 Subject: [PATCH 10/10] Update message_definitions/v1.0/development.xml Co-authored-by: Hamish Willee --- message_definitions/v1.0/development.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 63777e8876..aeceaff67e 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -54,7 +54,7 @@ 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. - The count field indicates the first index of the channel array that holds invalid data. + The count field indicates the first index of the channel array that is not used for channel data (this and later indexes are zero-filled). The RADIO_RC_CHANNELS_FLAGS_OUTDATED flag is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be validated so the last valid data is resent). 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 (it is up to the implementation of the receiver).