From 8b0d51c701ef582bccd18b617602843df7a457b9 Mon Sep 17 00:00:00 2001
From: Alexey <248997@gmail.com>
Date: Thu, 4 Jul 2024 16:23:11 +0500
Subject: [PATCH] feat(AsvRsga): Remove frequency parameter from SetMode
function
The frequency parameter has been removed from the SetMode function within the AsvRsgaServerEx, IAsvRsgaServerEx, AsvRsgaClientEx, and IAsvRsgaClientEx files. The 'SetMode' calls have been adjusted accordingly to reflect this change with the updated delegate signature.
---
.../shelved.patch | 265 ++++++++++++++++++
...e_Update_at_04_07_2024_13_22__Changes_.xml | 4 +
.../AsvRsga/Client/Ex/AsvRsgaClientEx.cs | 4 +-
.../AsvRsga/Client/Ex/IAsvRsgaClientEx.cs | 2 +-
.../Microservices/AsvRsga/RsgaHelper.cs | 15 +-
.../AsvRsga/Server/Ex/AsvRsgaServerEx.cs | 4 +-
.../AsvRsga/Server/Ex/IAsvRsgaServerEx.cs | 2 +-
.../Protocol/Dialects/asv_rsga.xml | 36 +--
8 files changed, 283 insertions(+), 49 deletions(-)
create mode 100644 src/.idea/.idea.Asv.Mavlink/.idea/shelf/Uncommitted_changes_before_Update_at_04_07_2024_13_22_[Changes]/shelved.patch
create mode 100644 src/.idea/.idea.Asv.Mavlink/.idea/shelf/Uncommitted_changes_before_Update_at_04_07_2024_13_22__Changes_.xml
diff --git a/src/.idea/.idea.Asv.Mavlink/.idea/shelf/Uncommitted_changes_before_Update_at_04_07_2024_13_22_[Changes]/shelved.patch b/src/.idea/.idea.Asv.Mavlink/.idea/shelf/Uncommitted_changes_before_Update_at_04_07_2024_13_22_[Changes]/shelved.patch
new file mode 100644
index 00000000..18714261
--- /dev/null
+++ b/src/.idea/.idea.Asv.Mavlink/.idea/shelf/Uncommitted_changes_before_Update_at_04_07_2024_13_22_[Changes]/shelved.patch
@@ -0,0 +1,265 @@
+Index: Asv.Mavlink/Protocol/Dialects/asv_sdr.xml
+IDEA additional info:
+Subsystem: com.intellij.openapi.diff.impl.patch.BaseRevisionTextPatchEP
+<+>\r\n\r\n \r\n \r\n \r\n \r\n \r\n \r\n \r\n \r\n common.xml\r\n \r\n \r\n \r\n \r\n \r\n \r\n Used to identify Software-defined radio payload in HEARTBEAT packet.\r\n \r\n \r\n \r\n \r\n \r\n Start one of ASV_SDR_CUSTOM_MODE. Can be used in the mission protocol for SDR payloads.\r\n Mode (uint32_t, see ASV_SDR_CUSTOM_MODE).\r\n Frequency in Hz, 0-3 bytes of uint_64, ignored for IDLE mode (uint32).\r\n Frequency in Hz, 4-7 bytes of uint_64, ignored for IDLE mode (uint32).\r\n Record rate in Hz, ignored for IDLE mode (float).\r\n Sending data thinning ratio. Each specified amount of recorded data will be skipped before it is sent over the communication channel. (uint32).\r\n Estimated reference power in dBm. Needed to tune the internal amplifiers and filters (float).\r\n Empty.\r\n \r\n \r\n Start recoring data with unique name (max 28 chars). Can be used in the mission protocol for SDR payloads.\r\n Record unique name: 0-3 chars (char[4]).\r\n Record unique name: 4-7 chars (char[4]).\r\n Record unique name: 8-11 chars (char[4]).\r\n Record unique name: 12-15 chars (char[4]).\r\n Record unique name: 16-19 chars (char[4]).\r\n Record unique name: 20-23 chars (char[4]).\r\n Record unique name: 24-27 chars (char[4]).\r\n \r\n \r\n Stop recoring data. Can be used in the mission protocol for SDR payloads.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n \r\n \r\n Set custom tag to current record. Can be used in the mission protocol for SDR payloads.\r\n ASV_SDR_RECORD_TAG_TYPE (uint32).\r\n Tag name: 0-3 chars (char[4]).\r\n Tag name: 4-7 chars (char[4]).\r\n Tag name: 8-11 chars (char[4]).\r\n Tag name: 12-15 chars (char[4]).\r\n Tag value data 0-3 bytes depends on the type of tag.\r\n Tag value data 4-7 bytes depends on the type of tag.\r\n \r\n \r\n Send shutdown or reboot command. Can't be used in the mission protocol for SDR payloads.\r\n ASV_SDR_SYSTEM_CONTROL_ACTION (uint32).\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n \r\n \r\n Waiting for a vehicle mission waypoint point. Only used in the mission protocol for SDR payloads.\r\n Waypoint index (uint32).\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n \r\n \r\n Waiting a certain amount of time. Only used in the mission protocol for SDR payloads.\r\n Delay in ms (uint32).\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n \r\n \r\n Starting mission, uploaded to SDR payload. Can't be used in the mission protocol for SDR payloads.\r\n Index of the task to start the mission (uint32).\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n \r\n \r\n Start mission, uploaded to SDR. Can't be used in the mission protocol for SDR payloads.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n \r\n \r\n Start calibration process. Can't be used in the mission protocol for SDR payloads.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n \r\n \r\n Stop calibration process. Can't be used in the mission protocol for SDR payloads.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n Empty.\r\n \r\n \r\n \r\n State of the current mission (unit8_t).\r\n \r\n Do nothing\r\n \r\n \r\n Mission in progress\r\n \r\n \r\n Mission failed\r\n \r\n \r\n \r\n \r\n Specifies the datatype of a record tag (unit8_t).\r\n \r\n 64-bit unsigned integer\r\n \r\n \r\n 64-bit signed integer\r\n \r\n \r\n 64-bit floating-point\r\n \r\n \r\n String type terminated by NULL if the length is less than 8 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 8 chars.\r\n \r\n \r\n \r\n A mapping of SDR payload modes for custom_mode field of heartbeat. Value of enum must be equal to message id from ASV_SDR_RECORD_DATA_* 13150-13199\r\n \r\n Default mode. Do nothing.\r\n \r\n \r\n Localizer measure mode. In this mode should send and record ASV_SDR_RECORD_DATA_LLZ\r\n \r\n \r\n Glide Path measure mode. In this mode should send and record ASV_SDR_RECORD_DATA_GP\r\n \r\n \r\n VOR measure mode. In this mode should send and record ASV_SDR_RECORD_DATA_VOR\r\n \r\n\r\n\r\n\r\n\r\n\r\n \r\n \r\n These flags encode supported mode.\r\n \r\n \r\n \r\n\r\n\r\n\r\n\r\n\r\n \r\n \r\n \r\n \r\n \r\n ACK / NACK / ERROR values as a result of ASV_SDR_*_REQUEST or ASV_SDR_*_DELETE commands.\r\n \r\n Request is ok.\r\n \r\n \r\n Command already in progress.\r\n \r\n \r\n Command error.\r\n \r\n \r\n Not supported command.\r\n \r\n \r\n \r\n \r\n SDR system control actions [!WRAP_TO_V2_EXTENSION_PACKET!]\r\n \r\n Request system reboot [!WRAP_TO_V2_EXTENSION_PACKET!]\r\n \r\n \r\n Request system shutdown [!WRAP_TO_V2_EXTENSION_PACKET!]\r\n \r\n \r\n Request software reboot [!WRAP_TO_V2_EXTENSION_PACKET!]\r\n \r\n \r\n \r\n \r\n Status of calibration process.\r\n \r\n Calibration not supported by device. Commands MAV_CMD_ASV_SDR_START_CALIBRATION and MAV_CMD_ASV_SDR_STOP_CALIBRATION not supported.\r\n \r\n \r\n Normal measure mode. Calibration table USED for measures.\r\n \r\n \r\n Calibration progress started. Table NOT! used for calculating values. All measures send as raw values.\r\n \r\n \r\n\r\n \r\n SDR signal transmition data type\r\n \r\n Write a value as a fraction between a given minimum and maximum. Uses 8 bits so we have '256' steps between min and max.\r\n \r\n \r\n Write a value as a fraction between a given minimum and maximum. Uses 16 bits so we have '65535' steps between min and max.\r\n \r\n \r\n Write a value as a float. Uses 32 bits.\r\n \r\n \r\n \r\n \r\n \r\n SDR payload status message. Send with 1 Hz frequency [!WRAP_TO_V2_EXTENSION_PACKET!].\r\n Supported ASV_SDR_CUSTOM_MODE.\r\n Number of records in storage.\r\n Total storage size in bytes.\r\n Record GUID. Also by this field we can understand if the data is currently being recorded (GUID!=0x00) or not (GUID==0x00).\r\n Current record mode (record data type).\r\n Record name, terminated by NULL if the length is less than 28 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 28 chars - applications have to provide 28+1 bytes storage if the name is stored as string. If the data is currently not being recorded, than return null; \r\n Mission state.\r\n Current mission index.\r\n \r\n Calibration status.\r\n Number of calibration tables.\r\n Estimated reference power in dBm. Entered in MAV_CMD_ASV_SDR_SET_MODE command.\r\n Input path signal overflow indicator. Relative value from 0.0 to 1.0.\r\n \r\n \r\n \r\n Request list of ASV_SDR_RECORD from the system/component.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID\r\n Component ID\r\n Specifies a unique number for this request. This allows the response packet to be identified.\r\n Specifies the start index of the records to be sent in the response.\r\n Specifies the number of records to be sent in the response after the skip index.\r\n \r\n \r\n Response for ASV_SDR_RECORD_REQUEST request. If success, device additional send ASV_SDR_RECORD items from start to stop index.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Result code.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Number of items ASV_SDR_RECORD for transmition after this request with success result code (depended from request).\r\n \r\n \r\n SDR payload record info.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Record GUID. Generated by payload after the start of recording.\r\n Record name, terminated by NULL if the length is less than 28 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 28 chars - applications have to provide 28+1 bytes storage if the name is stored as string.\r\n Record data type(it is also possible to know the type of data inside the record by cast enum to int).\r\n Reference frequency in Hz, specified by MAV_CMD_ASV_SDR_SET_MODE command.\r\n Created timestamp (UNIX epoch time).\r\n Record duration in sec.\r\n Tag items count.\r\n Data items count.\r\n Total data size of record with all data items and tags.\r\n \r\n \r\n Request to delete ASV_SDR_RECORD items from the system/component.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID.\r\n Component ID.\r\n Specifies a unique number for this request. This allows the response packet to be identified.\r\n Specifies GUID of the record to be deleted.\r\n \r\n \r\n Response for ASV_SDR_RECORD_DELETE_REQUEST.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Result code.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Specifies the GUID of the record that was deleted.\r\n \r\n \r\n \r\n Request list of ASV_SDR_RECORD_TAG from the system/component.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID\r\n Component ID\r\n Request unique number. This is to allow the response packet to be detected.\r\n Specifies the GUID of the record.\r\n Specifies the start index of the tag to be sent in the response.\r\n Specifies the number of tag to be sent in the response after the skip index.\r\n \r\n \r\n Response for ASV_SDR_RECORD_TAG_REQUEST. If success, device additional send ASV_SDR_RECORD_TAG items from start to stop index.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Result code.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Number of items ASV_SDR_RECORD_TAG for transmition after this request with success result code (depended from request).\r\n \r\n \r\n Request to read info with either tag_index and record_index from the system/component.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Record GUID.\r\n Tag GUID.\r\n Tag name, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string\r\n Tag type.\r\n Tag value, depends on the type of tag.\r\n \r\n \r\n Request to delete ASV_SDR_RECORD_TAG from the system/component.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID.\r\n Component ID.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Record GUID.\r\n Tag GUID.\r\n \r\n \r\n Response for ASV_SDR_RECORD_TAG_DELETE_REQUEST.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Result code.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Record GUID.\r\n Tag GUID.\r\n \r\n \r\n \r\n Request list of ASV_SDR_RECORD_DATA_* items from the system/component.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID\r\n Component ID\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Record GUID.\r\n Specifies the start index of the tag to be sent in the response.\r\n Specifies the number of tag to be sent in the response after the skip index.\r\n \r\n \r\n Response for ASV_SDR_RECORD_DATA_REQUEST. If success, device additional send ASV_SDR_RECORD_DATA_* items from start to stop index.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Result code.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Record GUID.\r\n Record data type(it is also possible to know the type of data inside the record by cast enum to int).\r\n Number of items ASV_SDR_RECORD_DATA_* for transmition after this request with success result code (depended from request).\r\n \r\n\r\n \r\n \r\n Response for ASV_SDR_CALIB_* requests. Result from ASV_SDR_CALIB_TABLE_READ, ASV_SDR_CALIB_TABLE_ROW_READ, ASV_SDR_CALIB_TABLE_UPLOAD_START messages.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Result code.\r\n \r\n \r\n Request to read ASV_SDR_CALIB_TABLE from the system/component. If success, device send ASV_SDR_CALIB_TABLE or ASV_SDR_CALIB_ACC, when error occured.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID\r\n Component ID\r\n Table index.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n \r\n \r\n Calibration table info.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Table index.\r\n Table name, terminated by NULL if the length is less than 28 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 28 chars - applications have to provide 28+1 bytes storage if the name is stored as string.\r\n Specifies the number of ROWs in the table.\r\n Updated timestamp (UNIX epoch time).\r\n \r\n \r\n Request to read ASV_SDR_CALIB_TABLE_ROW from the system/component. If success, device send ASV_SDR_CALIB_TABLE_ROW or ASV_SDR_CALIB_ACC, when error occured.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID.\r\n Component ID.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Table index.\r\n ROW index.\r\n \r\n \r\n Calibration ROW content.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID.\r\n Component ID.\r\n Table index.\r\n ROW index.\r\n Reference frequency in Hz.\r\n Reference power in dBm.\r\n Reference value.\r\n Adjustment for measured value (ref_value = measured_value + adjustment)\r\n \r\n \r\n Start uploading process. After that payload must send ASV_SDR_CALIB_TABLE_UPLOAD_READ_CALLBACK to client for reading table rows row_count times. Process end by payload with ASV_SDR_CALIB_ACC. [!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID.\r\n Component ID.\r\n Table index.\r\n Specifies the unique number of the original request. This allows the response to be matched to the correct request.\r\n Specifies the number of ROWs in the table.\r\n Current timestamp (UNIX epoch time).\r\n \r\n \r\n Read ASV_SDR_CALIB_TABLE_ROW callback from payload server to client. [!WRAP_TO_V2_EXTENSION_PACKET!]\r\n System ID.\r\n Component ID.\r\n Specifies the unique number of the original request from ASV_SDR_CALIB_TABLE_UPLOAD_START. This allows the response to be matched to the correct request.\r\n Table index.\r\n ROW index.\r\n \r\n \r\n \r\n \r\n Raw signal data for visualization.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Signal name, terminated by NULL if the length is less than 8 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 8+1 bytes storage if the ID is stored as string\r\n Timestamp (UNIX epoch time) for current set of measures.\r\n Format of one measure.\r\n Start index of measure set.\r\n Measures count in this packet.\r\n Total points in set.\r\n Min value of set.\r\n Max value of set.\r\n Data set of points.\r\n \r\n \r\n \r\n \r\n LLZ reciever record data.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Data index in record\r\n Record GUID.\r\n Timestamp (UNIX epoch time).\r\n \r\n GPS fix type.\r\n Latitude (WGS84, EGM96 ellipsoid)\r\n Longitude (WGS84, EGM96 ellipsoid)\r\n Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.\r\n GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX\r\n GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX\r\n GPS ground speed. If unknown, set to: UINT16_MAX\r\n Number of satellites visible. If unknown, set to 255\r\n Altitude (above WGS84, EGM96 ellipsoid). Positive for up.\r\n Position uncertainty. Positive for up.\r\n Altitude uncertainty. Positive for up.\r\n Speed uncertainty. Positive for up.\r\n \r\n Filtered global position latitude, expressed\r\n Filtered global position longitude, expressed\r\n Filtered global position altitude (MSL).\r\n Altitude above ground\r\n Ground X Speed (Latitude, positive north)\r\n Ground Y Speed (Longitude, positive east)\r\n Ground Z Speed (Altitude, positive down)\r\n Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX\r\n \r\n Roll angle (-pi..+pi)\r\n Pitch angle (-pi..+pi)\r\n Yaw angle (-pi..+pi)\r\n \r\n Input power of course.\r\n Carrier frequency offset of course.\r\n Aplitude modulation of 90Hz of course.\r\n Frequency offset of signal 90 Hz of course.\r\n Aplitude modulation of 150Hz of course.\r\n Frequency offset of signal 150 Hz of course.\r\n \r\n Input power of clearance.\r\n Carrier frequency offset of clearance.\r\n Aplitude modulation of 90Hz of clearance.\r\n Frequency offset of signal 90 Hz of clearance.\r\n Aplitude modulation of 150Hz of clearance.\r\n Frequency offset of signal 150 Hz of clearance.\r\n \r\n Measured frequency.\r\n Total carrier frequency offset.\r\n Total input power.\r\n Total field strength.\r\n \r\n Total aplitude modulation of 90Hz.\r\n Total frequency offset of signal 90 Hz.\r\n \r\n Total aplitude modulation of 150Hz.\r\n Total frequency offset of signal 150 Hz.\r\n\r\n Phase difference 90 Hz clearance and cource\r\n Phase difference 150 Hz clearance and cource.\r\n\r\n Total aplitude modulation of 90Hz.\r\n Total frequency offset of signal 90 Hz.\r\n Code identification\r\n\r\n Measure time.\r\n \r\n\r\n \r\n GP reciever record data.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Data index in record\r\n Record GUID.\r\n Timestamp (UNIX epoch time).\r\n \r\n GPS fix type.\r\n Latitude (WGS84, EGM96 ellipsoid)\r\n Longitude (WGS84, EGM96 ellipsoid)\r\n Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.\r\n GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX\r\n GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX\r\n GPS ground speed. If unknown, set to: UINT16_MAX\r\n Number of satellites visible. If unknown, set to 255\r\n Altitude (above WGS84, EGM96 ellipsoid). Positive for up.\r\n Position uncertainty. Positive for up.\r\n Altitude uncertainty. Positive for up.\r\n Speed uncertainty. Positive for up.\r\n \r\n Filtered global position latitude, expressed\r\n Filtered global position longitude, expressed\r\n Filtered global position altitude (MSL).\r\n Altitude above ground\r\n Ground X Speed (Latitude, positive north)\r\n Ground Y Speed (Longitude, positive east)\r\n Ground Z Speed (Altitude, positive down)\r\n Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX\r\n \r\n Roll angle (-pi..+pi)\r\n Pitch angle (-pi..+pi)\r\n Yaw angle (-pi..+pi)\r\n \r\n Input power of course.\r\n Carrier frequency offset of course.\r\n Aplitude modulation of 90Hz of course.\r\n Frequency offset of signal 90 Hz of course.\r\n Aplitude modulation of 150Hz of course.\r\n Frequency offset of signal 150 Hz of course.\r\n \r\n Input power of clearance.\r\n Carrier frequency offset of clearance.\r\n Aplitude modulation of 90Hz of clearance.\r\n Frequency offset of signal 90 Hz of clearance.\r\n Aplitude modulation of 150Hz of clearance.\r\n Frequency offset of signal 150 Hz of clearance.\r\n \r\n Measured frequency.\r\n Total carrier frequency offset.\r\n Total input power.\r\n Total field strength.\r\n\r\n Total aplitude modulation of 90Hz.\r\n Total frequency offset of signal 90 Hz.\r\n\r\n Total aplitude modulation of 150Hz.\r\n Total frequency offset of signal 150 Hz.\r\n\r\n Phase difference 90 Hz clearance and cource\r\n Phase difference 150 Hz clearance and cource.\r\n\r\n Measure time.\r\n \r\n \r\n \r\n VOR reciever record data.[!WRAP_TO_V2_EXTENSION_PACKET!]\r\n Data index in record\r\n Record GUID.\r\n Timestamp (UNIX epoch time).\r\n \r\n GPS fix type.\r\n Latitude (WGS84, EGM96 ellipsoid)\r\n Longitude (WGS84, EGM96 ellipsoid)\r\n Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.\r\n GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX\r\n GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX\r\n GPS ground speed. If unknown, set to: UINT16_MAX\r\n Number of satellites visible. If unknown, set to 255\r\n Altitude (above WGS84, EGM96 ellipsoid). Positive for up.\r\n Position uncertainty. Positive for up.\r\n Altitude uncertainty. Positive for up.\r\n Speed uncertainty. Positive for up.\r\n \r\n Filtered global position latitude, expressed\r\n Filtered global position longitude, expressed\r\n Filtered global position altitude (MSL).\r\n Altitude above ground\r\n Ground X Speed (Latitude, positive north)\r\n Ground Y Speed (Longitude, positive east)\r\n Ground Z Speed (Altitude, positive down)\r\n Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX\r\n \r\n Roll angle (-pi..+pi)\r\n Pitch angle (-pi..+pi)\r\n Yaw angle (-pi..+pi)\r\n \r\n Measured frequency.\r\n Total carrier frequency offset.\r\n Measured azimuth.\r\n Total input power.\r\n Total field strength.\r\n \r\n Total aplitude modulation of 30 Hz.\r\n Total frequency offset of signal 30 Hz.\r\n \r\n Total aplitude modulation of 9960 Hz.\r\n Total frequency offset of signal 9960 Hz.\r\n\r\n Deviation.\r\n \r\n Total aplitude modulation of 90Hz.\r\n Total frequency offset of signal 90 Hz.\r\n Code identification\r\n\r\n Measure time.\r\n \r\n \r\n \r\n\r\n
+Subsystem: com.intellij.openapi.diff.impl.patch.CharsetEP
+<+>UTF-8
+===================================================================
+diff --git a/Asv.Mavlink/Protocol/Dialects/asv_sdr.xml b/Asv.Mavlink/Protocol/Dialects/asv_sdr.xml
+--- a/Asv.Mavlink/Protocol/Dialects/asv_sdr.xml (revision 2791709e6bfaf02007a2f646eeca4186cb05a70a)
++++ b/Asv.Mavlink/Protocol/Dialects/asv_sdr.xml (date 1719866535295)
+@@ -469,16 +469,16 @@
+
+ Input power of course.
+ Carrier frequency offset of course.
+- Aplitude modulation of 90Hz of course.
++ Amplitude modulation of 90Hz of course.
+ Frequency offset of signal 90 Hz of course.
+- Aplitude modulation of 150Hz of course.
++ Amplitude modulation of 150Hz of course.
+ Frequency offset of signal 150 Hz of course.
+
+ Input power of clearance.
+ Carrier frequency offset of clearance.
+- Aplitude modulation of 90Hz of clearance.
++ Amplitude modulation of 90Hz of clearance.
+ Frequency offset of signal 90 Hz of clearance.
+- Aplitude modulation of 150Hz of clearance.
++ Amplitude modulation of 150Hz of clearance.
+ Frequency offset of signal 150 Hz of clearance.
+
+ Measured frequency.
+@@ -486,16 +486,16 @@
+ Total input power.
+ Total field strength.
+
+- Total aplitude modulation of 90Hz.
++ Total amplitude modulation of 90Hz.
+ Total frequency offset of signal 90 Hz.
+
+- Total aplitude modulation of 150Hz.
++ Total amplitude modulation of 150Hz.
+ Total frequency offset of signal 150 Hz.
+
+ Phase difference 90 Hz clearance and cource
+ Phase difference 150 Hz clearance and cource.
+
+- Total aplitude modulation of 90Hz.
++ Total amplitude modulation of 90Hz.
+ Total frequency offset of signal 90 Hz.
+ Code identification
+
+@@ -536,16 +536,16 @@
+
+ Input power of course.
+ Carrier frequency offset of course.
+- Aplitude modulation of 90Hz of course.
++ Amplitude modulation of 90Hz of course.
+ Frequency offset of signal 90 Hz of course.
+- Aplitude modulation of 150Hz of course.
++ Amplitude modulation of 150Hz of course.
+ Frequency offset of signal 150 Hz of course.
+
+ Input power of clearance.
+ Carrier frequency offset of clearance.
+- Aplitude modulation of 90Hz of clearance.
++ Amplitude modulation of 90Hz of clearance.
+ Frequency offset of signal 90 Hz of clearance.
+- Aplitude modulation of 150Hz of clearance.
++ Amplitude modulation of 150Hz of clearance.
+ Frequency offset of signal 150 Hz of clearance.
+
+ Measured frequency.
+@@ -553,10 +553,10 @@
+ Total input power.
+ Total field strength.
+
+- Total aplitude modulation of 90Hz.
++ Total amplitude modulation of 90Hz.
+ Total frequency offset of signal 90 Hz.
+
+- Total aplitude modulation of 150Hz.
++ Total amplitude modulation of 150Hz.
+ Total frequency offset of signal 150 Hz.
+
+ Phase difference 90 Hz clearance and cource
+@@ -603,15 +603,15 @@
+ Total input power.
+ Total field strength.
+
+- Total aplitude modulation of 30 Hz.
++ Total amplitude modulation of 30 Hz.
+ Total frequency offset of signal 30 Hz.
+
+- Total aplitude modulation of 9960 Hz.
++ Total amplitude modulation of 9960 Hz.
+ Total frequency offset of signal 9960 Hz.
+
+ Deviation.
+
+- Total aplitude modulation of 90Hz.
++ Total amplitude modulation of 90Hz.
+ Total frequency offset of signal 90 Hz.
+ Code identification
+
+Index: Asv.Mavlink/Protocol/Dialects/asv_rsga.xml
+IDEA additional info:
+Subsystem: com.intellij.openapi.diff.impl.patch.CharsetEP
+<+>UTF-8
+===================================================================
+diff --git a/Asv.Mavlink/Protocol/Dialects/asv_rsga.xml b/Asv.Mavlink/Protocol/Dialects/asv_rsga.xml
+new file mode 100644
+--- /dev/null (date 1719877112198)
++++ b/Asv.Mavlink/Protocol/Dialects/asv_rsga.xml (date 1719877112198)
+@@ -0,0 +1,151 @@
++
++
++
++
++
++
++
++
++
++ minimal.xml
++ asv_table.xml
++
++
++
++
++
++ Used to identify Radio Signal Generator and Analyser(RSGA) payload in HEARTBEAT packet.
++
++
++
++
++ A mapping of RSGA modes for custom_mode field of heartbeat.
++
++ Default mode. Do nothing.
++
++
++ Localizer generator mode.
++
++
++ Glide Path generator mode.
++
++
++ VOR generator mode.
++
++
++ Marker generator mode.
++
++
++ DME requester mode.
++
++
++ DME responder mode.
++
++
++ Error mode.
++
++
++
++
++ ACK / NACK / ERROR values as a result of ASV_RSGA_*_REQUEST commands.
++
++ Request is ok.
++
++
++ Already in progress.
++
++
++ Internal error.
++
++
++ Not supported.
++
++
++ Not found.
++
++
++
++
++
++
++
++
++ Do set mode
++ Mode (uint32_t, see ASV_RSGA_CUSTOM_MODE).
++ Empty.
++ Empty.
++ Empty.
++ Empty.
++ Empty.
++ Empty.
++
++
++
++
++
++ Requests device COMPATIBILITY. Returns ASV_RSGA_COMPATIBILITY_RESPONSE. [!WRAP_TO_V2_EXTENSION_PACKET!]
++ System ID.
++ Component ID.
++ Specifies a unique number for this request. This allows the response packet to be identified.
++
++
++ Responds to the ASV_RSGA_COMPATIBILITY_REQUEST. [!WRAP_TO_V2_EXTENSION_PACKET!]
++ Result code.
++ Specifies the unique number of the original request. This allows the response to be matched to the correct request.
++ Supported modes. Each bit index represents an ASV_RSGA_CUSTOM_MODE value (256 bits). First (IDLE) and last(ERROR) bits always true.
++
++
++
++ Requests device COMPATIBILITY. Returns ASV_RSGA_COMPATIBILITY_RESPONSE. [!WRAP_TO_V2_EXTENSION_PACKET!]
++ System ID.
++ Component ID.
++ Specifies a unique number for this request. This allows the response packet to be identified.
++
++
++ Requests device COMPATIBILITY. Returns ASV_RSGA_COMPATIBILITY_RESPONSE. [!WRAP_TO_V2_EXTENSION_PACKET!]
++ System ID.
++ Component ID.
++ Specifies a unique number for this request. This allows the response packet to be identified.
++
++
++
++
++
++
diff --git a/src/.idea/.idea.Asv.Mavlink/.idea/shelf/Uncommitted_changes_before_Update_at_04_07_2024_13_22__Changes_.xml b/src/.idea/.idea.Asv.Mavlink/.idea/shelf/Uncommitted_changes_before_Update_at_04_07_2024_13_22__Changes_.xml
new file mode 100644
index 00000000..58375888
--- /dev/null
+++ b/src/.idea/.idea.Asv.Mavlink/.idea/shelf/Uncommitted_changes_before_Update_at_04_07_2024_13_22__Changes_.xml
@@ -0,0 +1,4 @@
+
+
+
+
\ No newline at end of file
diff --git a/src/Asv.Mavlink/Microservices/AsvRsga/Client/Ex/AsvRsgaClientEx.cs b/src/Asv.Mavlink/Microservices/AsvRsga/Client/Ex/AsvRsgaClientEx.cs
index 9e2cb00c..22d649ec 100644
--- a/src/Asv.Mavlink/Microservices/AsvRsga/Client/Ex/AsvRsgaClientEx.cs
+++ b/src/Asv.Mavlink/Microservices/AsvRsga/Client/Ex/AsvRsgaClientEx.cs
@@ -46,10 +46,10 @@ public Task RefreshInfo(CancellationToken cancel = default)
return Base.GetCompatibilities(cancel);
}
- public async Task SetMode(AsvRsgaCustomMode mode, ulong frequencyHz, CancellationToken cancel = default)
+ public async Task SetMode(AsvRsgaCustomMode mode, CancellationToken cancel = default)
{
using var cs = CancellationTokenSource.CreateLinkedTokenSource(DisposeCancel, cancel);
- var result = await _commandClient.CommandLong(item => RsgaHelper.SetArgsForSetMode(item, mode,frequencyHz),cs.Token).ConfigureAwait(false);
+ var result = await _commandClient.CommandLong(item => RsgaHelper.SetArgsForSetMode(item, mode),cs.Token).ConfigureAwait(false);
return result.Result;
}
}
\ No newline at end of file
diff --git a/src/Asv.Mavlink/Microservices/AsvRsga/Client/Ex/IAsvRsgaClientEx.cs b/src/Asv.Mavlink/Microservices/AsvRsga/Client/Ex/IAsvRsgaClientEx.cs
index 3c699c81..9f451a49 100644
--- a/src/Asv.Mavlink/Microservices/AsvRsga/Client/Ex/IAsvRsgaClientEx.cs
+++ b/src/Asv.Mavlink/Microservices/AsvRsga/Client/Ex/IAsvRsgaClientEx.cs
@@ -14,5 +14,5 @@ public interface IAsvRsgaClientEx
IAsvRsgaClient Base { get; }
IObservable> AvailableModes { get; }
Task RefreshInfo(CancellationToken cancel = default);
- Task SetMode(AsvRsgaCustomMode mode, ulong frequencyHz, CancellationToken cancel = default);
+ Task SetMode(AsvRsgaCustomMode mode, CancellationToken cancel = default);
}
\ No newline at end of file
diff --git a/src/Asv.Mavlink/Microservices/AsvRsga/RsgaHelper.cs b/src/Asv.Mavlink/Microservices/AsvRsga/RsgaHelper.cs
index ddbe565a..0d51e531 100644
--- a/src/Asv.Mavlink/Microservices/AsvRsga/RsgaHelper.cs
+++ b/src/Asv.Mavlink/Microservices/AsvRsga/RsgaHelper.cs
@@ -8,28 +8,25 @@ namespace Asv.Mavlink;
public class RsgaHelper
{
- public static void SetArgsForSetMode(CommandLongPayload item, AsvRsgaCustomMode mode,ulong frequencyHz)
+ public static void SetArgsForSetMode(CommandLongPayload item, AsvRsgaCustomMode mode)
{
- var freqArray = BitConverter.GetBytes(frequencyHz);
+
item.Command = (V2.Common.MavCmd)V2.AsvRsga.MavCmd.MavCmdAsvRsgaSetMode;
item.Param1 = BitConverter.ToSingle(BitConverter.GetBytes((uint)mode));
- item.Param2 = BitConverter.ToSingle(freqArray, 0);
- item.Param3 = BitConverter.ToSingle(freqArray, 4);
+ item.Param2 = float.NaN;
+ item.Param3 = float.NaN;
item.Param4 = float.NaN;
item.Param5 = float.NaN;
item.Param6 = float.NaN;
item.Param7 = float.NaN;
}
- public static void GetArgsForSetMode(CommandLongPayload item, out AsvRsgaCustomMode mode, out ulong frequencyHz)
+ public static void GetArgsForSetMode(CommandLongPayload item, out AsvRsgaCustomMode mode)
{
if (item.Command != (V2.Common.MavCmd)V2.AsvRsga.MavCmd.MavCmdAsvRsgaSetMode)
throw new ArgumentException($"Command {item.Command:G} is not {V2.AsvRsga.MavCmd.MavCmdAsvRsgaSetMode:G}");
mode = (AsvRsgaCustomMode)BitConverter.ToUInt32(BitConverter.GetBytes(item.Param1));
- var freqArray = new byte[8];
- BitConverter.GetBytes(item.Param2).CopyTo(freqArray,0);
- BitConverter.GetBytes(item.Param3).CopyTo(freqArray,4);
- frequencyHz = BitConverter.ToUInt64(freqArray,0);
+
}
public static void SetSupportedModes(AsvRsgaCompatibilityResponsePayload payload, IEnumerable modes)
diff --git a/src/Asv.Mavlink/Microservices/AsvRsga/Server/Ex/AsvRsgaServerEx.cs b/src/Asv.Mavlink/Microservices/AsvRsga/Server/Ex/AsvRsgaServerEx.cs
index d64e0122..e0ebc40d 100644
--- a/src/Asv.Mavlink/Microservices/AsvRsga/Server/Ex/AsvRsgaServerEx.cs
+++ b/src/Asv.Mavlink/Microservices/AsvRsga/Server/Ex/AsvRsgaServerEx.cs
@@ -20,8 +20,8 @@ public AsvRsgaServerEx(IAsvRsgaServer server, IStatusTextServer status, ICommand
{
if (SetMode == null) return new CommandResult(MavResult.MavResultUnsupported);
using var cs = CancellationTokenSource.CreateLinkedTokenSource(DisposeCancel, cancel);
- RsgaHelper.GetArgsForSetMode(args.Payload, out var mode, out var freq);
- var result = await SetMode(mode,freq, cs.Token).ConfigureAwait(false);
+ RsgaHelper.GetArgsForSetMode(args.Payload, out var mode);
+ var result = await SetMode(mode, cs.Token).ConfigureAwait(false);
return new CommandResult(result);
};
}
diff --git a/src/Asv.Mavlink/Microservices/AsvRsga/Server/Ex/IAsvRsgaServerEx.cs b/src/Asv.Mavlink/Microservices/AsvRsga/Server/Ex/IAsvRsgaServerEx.cs
index 595f9f44..833e9812 100644
--- a/src/Asv.Mavlink/Microservices/AsvRsga/Server/Ex/IAsvRsgaServerEx.cs
+++ b/src/Asv.Mavlink/Microservices/AsvRsga/Server/Ex/IAsvRsgaServerEx.cs
@@ -7,7 +7,7 @@
namespace Asv.Mavlink;
-public delegate Task RsgaSetMode(AsvRsgaCustomMode mode, ulong freq, CancellationToken cancel = default);
+public delegate Task RsgaSetMode(AsvRsgaCustomMode mode, CancellationToken cancel = default);
public delegate IEnumerable RsgaGetCompatibility();
public interface IAsvRsgaServerEx
diff --git a/src/Asv.Mavlink/Protocol/Dialects/asv_rsga.xml b/src/Asv.Mavlink/Protocol/Dialects/asv_rsga.xml
index 7c94762f..424d58a5 100644
--- a/src/Asv.Mavlink/Protocol/Dialects/asv_rsga.xml
+++ b/src/Asv.Mavlink/Protocol/Dialects/asv_rsga.xml
@@ -65,8 +65,8 @@
Do set mode
Mode (uint32_t, see ASV_RSGA_CUSTOM_MODE).
- Frequency in Hz, 0-3 bytes of uint_64, ignored for IDLE mode (uint32).
- Frequency in Hz, 4-7 bytes of uint_64, ignored for IDLE mode (uint32).
+ Empty.
+ Empty.
Empty.
Empty.
Empty.
@@ -87,39 +87,7 @@
Specifies the unique number of the original request. This allows the response to be matched to the correct request.Supported modes. Each bit index represents an ASV_RSGA_CUSTOM_MODE value (256 bits). First (IDLE) bit always true.
-
-