From a870ebaf349aa4ca13fd3de50604649dda47215b Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Thu, 22 Dec 2022 02:39:18 -0500 Subject: [PATCH 1/8] add cellular status to telem server and telem --- protos/telemetry/telemetry.proto | 30 +++++++++++++++++++ .../telemetry_server/telemetry_server.proto | 21 +++++++++++++ 2 files changed, 51 insertions(+) diff --git a/protos/telemetry/telemetry.proto b/protos/telemetry/telemetry.proto index 6dc1bff61..70657d04b 100644 --- a/protos/telemetry/telemetry.proto +++ b/protos/telemetry/telemetry.proto @@ -48,6 +48,8 @@ service TelemetryService { rpc SubscribeHealth(SubscribeHealthRequest) returns(stream HealthResponse) {} // Subscribe to 'RC status' updates. rpc SubscribeRcStatus(SubscribeRcStatusRequest) returns(stream RcStatusResponse) {} + // Subscribe to 'Cellular status' updates. + rpc SubscribeCellularStatus(SubscribeCellularStatusRequest) returns(stream CellularStatusResponse) {} // Subscribe to 'status text' updates. rpc SubscribeStatusText(SubscribeStatusTextRequest) returns(stream StatusTextResponse) {} // Subscribe to 'actuator control target' updates. @@ -105,6 +107,8 @@ service TelemetryService { rpc SetRateBattery(SetRateBatteryRequest) returns(SetRateBatteryResponse) {} // Set rate to 'RC status' updates. rpc SetRateRcStatus(SetRateRcStatusRequest) returns(SetRateRcStatusResponse) {} + // Set rate to 'Cellular status' updates. + rpc SetRateCellularStatus(SetRateCellularStatusRequest) returns(SetRateCellularStatusResponse) {} // Set rate to 'actuator control target' updates. rpc SetRateActuatorControlTarget(SetRateActuatorControlTargetRequest) returns(SetRateActuatorControlTargetResponse) {} // Set rate to 'actuator output status' updates. @@ -226,6 +230,11 @@ message RcStatusResponse { RcStatus rc_status = 1; // The next RC status } +message SubscribeCellularStatusRequest {} +message CellularStatusResponse { + CellularStatus cellular_status = 1; // The next RC status +} + message SubscribeStatusTextRequest {} message StatusTextResponse { StatusText status_text = 1; // The next 'status text' @@ -404,10 +413,19 @@ message SetRateBatteryResponse { message SetRateRcStatusRequest { double rate_hz = 1; // The requested rate (in Hertz) } + +message SetRateCellularStatusRequest { + double rate_hz = 1; // The requested rate (in Hertz) +} + message SetRateRcStatusResponse { TelemetryResult telemetry_result = 1; } +message SetRateCellularStatusResponse { + TelemetryResult telemetry_result = 1; +} + message SetRateActuatorControlTargetRequest { double rate_hz = 1; // The requested rate (in Hertz) } @@ -643,6 +661,18 @@ message RcStatus { float signal_strength_percent = 3 [(mavsdk.options.default_value)="NaN"]; // Signal strength (range: 0 to 100, NaN if unknown) } +// Cellular modem status type. +message CellularStatus { + uint32 id = 1;// (actually uint8_t) + uint32 status = 2;// (actually uint8_t) + uint32 failure_reason = 3; // (actually uint8_t) + uint32 type = 4; //(actually uint8_t) + uint32 quality = 5; // Signal strength + uint32 mcc = 6; // (actually uint16_t) + uint32 mnc = 7; // (actually uint16_t) + uint32 lac = 8; // (actually uint16_t) +} + // Status types. enum StatusTextType { STATUS_TEXT_TYPE_DEBUG = 0; // Debug diff --git a/protos/telemetry_server/telemetry_server.proto b/protos/telemetry_server/telemetry_server.proto index d4a47a7cb..a031bb75e 100644 --- a/protos/telemetry_server/telemetry_server.proto +++ b/protos/telemetry_server/telemetry_server.proto @@ -24,6 +24,8 @@ service TelemetryServerService { rpc PublishRawGps(PublishRawGpsRequest) returns(PublishRawGpsResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'battery' updates. rpc PublishBattery(PublishBatteryRequest) returns(PublishBatteryResponse) { option (mavsdk.options.async_type) = SYNC; } + // Publish to 'cellular_status' updates. + rpc PublishCellularStatus(PublishCellularStatusRequest) returns(PublishCellularStatusResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'status text' updates. rpc PublishStatusText(PublishStatusTextRequest) returns(PublishStatusTextResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'odometry' updates. @@ -83,6 +85,10 @@ message PublishBatteryRequest { Battery battery = 1; // The next 'battery' state } +message PublishCellularStatusRequest { + CellularStatus cellular_status = 1; // The next Cellular status +} + message PublishRcStatusRequest { RcStatus rc_status = 1; // The next RC status } @@ -143,6 +149,9 @@ message PublishBatteryResponse { TelemetryServerResult telemetry_server_result = 1; } +message PublishCellularStatusResponse { + TelemetryServerResult telemetry_server_result = 1; +} message PublishStatusTextResponse { TelemetryServerResult telemetry_server_result = 1; @@ -294,6 +303,18 @@ message RcStatus { float signal_strength_percent = 3 [(mavsdk.options.default_value)="NaN"]; // Signal strength (range: 0 to 100, NaN if unknown) } +// Cellular modem status type. +message CellularStatus { + uint32 id = 1;// (actually uint8_t) + uint32 status = 2;// (actually uint8_t) + uint32 failure_reason = 3; // (actually uint8_t) + uint32 type = 4; //(actually uint8_t) + uint32 quality = 5; // Signal strength + uint32 mcc = 6; // (actually uint16_t) + uint32 mnc = 7; // (actually uint16_t) + uint32 lac = 8; // (actually uint16_t) +} + // Status types. enum StatusTextType { STATUS_TEXT_TYPE_DEBUG = 0; // Debug From 532769086c13bb0d279a97bd39d9193f0ec8edc2 Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Tue, 17 Jan 2023 19:22:47 -0500 Subject: [PATCH 2/8] expand cellular_status msg --- protos/telemetry/telemetry.proto | 8 ++++++++ protos/telemetry_server/telemetry_server.proto | 8 ++++++++ 2 files changed, 16 insertions(+) diff --git a/protos/telemetry/telemetry.proto b/protos/telemetry/telemetry.proto index 70657d04b..64c83b4bb 100644 --- a/protos/telemetry/telemetry.proto +++ b/protos/telemetry/telemetry.proto @@ -671,6 +671,14 @@ message CellularStatus { uint32 mcc = 6; // (actually uint16_t) uint32 mnc = 7; // (actually uint16_t) uint32 lac = 8; // (actually uint16_t) + uint32 slot_number = 9; //(actually uint8_t) + uint32 rx_level = 10; //(actually uint8_t) + uint32 signal_to_noise = 11; //(actually uint8_t) + uint32 band_number = 12; //(actually uint8_t) + uint32 arfcn = 13; + uint32 cell_id = 14; // char[9] + float download_rate = 15; + float upload_rate = 16; } // Status types. diff --git a/protos/telemetry_server/telemetry_server.proto b/protos/telemetry_server/telemetry_server.proto index a031bb75e..e647e49ad 100644 --- a/protos/telemetry_server/telemetry_server.proto +++ b/protos/telemetry_server/telemetry_server.proto @@ -313,6 +313,14 @@ message CellularStatus { uint32 mcc = 6; // (actually uint16_t) uint32 mnc = 7; // (actually uint16_t) uint32 lac = 8; // (actually uint16_t) + uint32 slot_number = 9; //(actually uint8_t) + uint32 rx_level = 10; //(actually uint8_t) + uint32 signal_to_noise = 11; //(actually uint8_t) + uint32 band_number = 12; //(actually uint8_t) + uint32 arfcn = 13; + uint32 cell_id = 14; // char[9] + float download_rate = 15; + float upload_rate = 16; } // Status types. From 5be691163cd85ade69f703e75fe25ae2c5d2ce5b Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Tue, 17 Jan 2023 21:12:25 -0500 Subject: [PATCH 3/8] change cell id to string --- protos/telemetry/telemetry.proto | 2 +- protos/telemetry_server/telemetry_server.proto | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/protos/telemetry/telemetry.proto b/protos/telemetry/telemetry.proto index 64c83b4bb..96a65b268 100644 --- a/protos/telemetry/telemetry.proto +++ b/protos/telemetry/telemetry.proto @@ -676,7 +676,7 @@ message CellularStatus { uint32 signal_to_noise = 11; //(actually uint8_t) uint32 band_number = 12; //(actually uint8_t) uint32 arfcn = 13; - uint32 cell_id = 14; // char[9] + string cell_id = 14; // char[9] float download_rate = 15; float upload_rate = 16; } diff --git a/protos/telemetry_server/telemetry_server.proto b/protos/telemetry_server/telemetry_server.proto index e647e49ad..6f677bc61 100644 --- a/protos/telemetry_server/telemetry_server.proto +++ b/protos/telemetry_server/telemetry_server.proto @@ -318,7 +318,7 @@ message CellularStatus { uint32 signal_to_noise = 11; //(actually uint8_t) uint32 band_number = 12; //(actually uint8_t) uint32 arfcn = 13; - uint32 cell_id = 14; // char[9] + string cell_id = 14; // char[9] float download_rate = 15; float upload_rate = 16; } From 82c5ffc9ec27a36458fa4ca1a01034f436909adf Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Thu, 26 Jan 2023 23:14:53 -0500 Subject: [PATCH 4/8] update cellular_status extensions --- protos/telemetry/telemetry.proto | 34 ++++++++++--------- .../telemetry_server/telemetry_server.proto | 34 ++++++++++--------- 2 files changed, 36 insertions(+), 32 deletions(-) diff --git a/protos/telemetry/telemetry.proto b/protos/telemetry/telemetry.proto index 96a65b268..abd0e130b 100644 --- a/protos/telemetry/telemetry.proto +++ b/protos/telemetry/telemetry.proto @@ -663,22 +663,24 @@ message RcStatus { // Cellular modem status type. message CellularStatus { - uint32 id = 1;// (actually uint8_t) - uint32 status = 2;// (actually uint8_t) - uint32 failure_reason = 3; // (actually uint8_t) - uint32 type = 4; //(actually uint8_t) - uint32 quality = 5; // Signal strength - uint32 mcc = 6; // (actually uint16_t) - uint32 mnc = 7; // (actually uint16_t) - uint32 lac = 8; // (actually uint16_t) - uint32 slot_number = 9; //(actually uint8_t) - uint32 rx_level = 10; //(actually uint8_t) - uint32 signal_to_noise = 11; //(actually uint8_t) - uint32 band_number = 12; //(actually uint8_t) - uint32 arfcn = 13; - string cell_id = 14; // char[9] - float download_rate = 15; - float upload_rate = 16; + uint32 status = 1; + uint32 failure_reason = 2; + uint32 type = 3; + uint32 quality = 4; + uint32 mcc = 5; + uint32 mnc = 6; + uint32 lac = 7; + uint32 instance_number = 8; + uint64 download_rate = 9; + uint64 upload_rate = 10; + uint64 bit_error_rate = 11; + float rx_level = 12; + float tx_level = 13; + float signal_to_noise = 14; + string cell_tower_id = 15; + uint32 band_number = 16; + float band_frequency = 17; + float arfcn = 18;//Absolute radio-frequency channel number } // Status types. diff --git a/protos/telemetry_server/telemetry_server.proto b/protos/telemetry_server/telemetry_server.proto index 6f677bc61..6d2b5753b 100644 --- a/protos/telemetry_server/telemetry_server.proto +++ b/protos/telemetry_server/telemetry_server.proto @@ -305,22 +305,24 @@ message RcStatus { // Cellular modem status type. message CellularStatus { - uint32 id = 1;// (actually uint8_t) - uint32 status = 2;// (actually uint8_t) - uint32 failure_reason = 3; // (actually uint8_t) - uint32 type = 4; //(actually uint8_t) - uint32 quality = 5; // Signal strength - uint32 mcc = 6; // (actually uint16_t) - uint32 mnc = 7; // (actually uint16_t) - uint32 lac = 8; // (actually uint16_t) - uint32 slot_number = 9; //(actually uint8_t) - uint32 rx_level = 10; //(actually uint8_t) - uint32 signal_to_noise = 11; //(actually uint8_t) - uint32 band_number = 12; //(actually uint8_t) - uint32 arfcn = 13; - string cell_id = 14; // char[9] - float download_rate = 15; - float upload_rate = 16; + uint32 status = 1; + uint32 failure_reason = 2; + uint32 type = 3; + uint32 quality = 4; + uint32 mcc = 5; + uint32 mnc = 6; + uint32 lac = 7; + uint32 instance_number = 8; + uint64 download_rate = 9; + uint64 upload_rate = 10; + uint64 bit_error_rate = 11; + float rx_level = 12; + float tx_level = 13; + float signal_to_noise = 14; + string cell_tower_id = 15; + uint32 band_number = 16; + float band_frequency = 17; + float arfcn = 18;//Absolute radio-frequency channel number } // Status types. From e31ae97f3435c5ae299d25d3dda0410a5e295a57 Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Thu, 26 Jan 2023 23:29:03 -0500 Subject: [PATCH 5/8] add nic info message --- protos/telemetry/telemetry.proto | 32 ++++++++++++++++++- .../telemetry_server/telemetry_server.proto | 22 +++++++++++++ 2 files changed, 53 insertions(+), 1 deletion(-) diff --git a/protos/telemetry/telemetry.proto b/protos/telemetry/telemetry.proto index abd0e130b..de66e7639 100644 --- a/protos/telemetry/telemetry.proto +++ b/protos/telemetry/telemetry.proto @@ -50,6 +50,8 @@ service TelemetryService { rpc SubscribeRcStatus(SubscribeRcStatusRequest) returns(stream RcStatusResponse) {} // Subscribe to 'Cellular status' updates. rpc SubscribeCellularStatus(SubscribeCellularStatusRequest) returns(stream CellularStatusResponse) {} + // Subscribe to 'NIC_INFO' updates. + rpc SubscribeNicInfo(SubscribeNicInfoRequest) returns(stream NicInfoResponse) {} // Subscribe to 'status text' updates. rpc SubscribeStatusText(SubscribeStatusTextRequest) returns(stream StatusTextResponse) {} // Subscribe to 'actuator control target' updates. @@ -109,6 +111,8 @@ service TelemetryService { rpc SetRateRcStatus(SetRateRcStatusRequest) returns(SetRateRcStatusResponse) {} // Set rate to 'Cellular status' updates. rpc SetRateCellularStatus(SetRateCellularStatusRequest) returns(SetRateCellularStatusResponse) {} + // Set rate to 'NIC_INFO' updates. + rpc SetRateNicInfo(SetRateNicInfoRequest) returns(SetRateNicInfoResponse) {} // Set rate to 'actuator control target' updates. rpc SetRateActuatorControlTarget(SetRateActuatorControlTargetRequest) returns(SetRateActuatorControlTargetResponse) {} // Set rate to 'actuator output status' updates. @@ -232,9 +236,15 @@ message RcStatusResponse { message SubscribeCellularStatusRequest {} message CellularStatusResponse { - CellularStatus cellular_status = 1; // The next RC status + CellularStatus cellular_status = 1; // The next cellular status } +message SubscribeNicInfoRequest {} +message NicInfoResponse { + NicInfo nic_info = 1; // The next nic info +} + + message SubscribeStatusTextRequest {} message StatusTextResponse { StatusText status_text = 1; // The next 'status text' @@ -418,6 +428,11 @@ message SetRateCellularStatusRequest { double rate_hz = 1; // The requested rate (in Hertz) } +message SetRateNicInfoRequest { + double rate_hz = 1; // The requested rate (in Hertz) +} + + message SetRateRcStatusResponse { TelemetryResult telemetry_result = 1; } @@ -426,6 +441,10 @@ message SetRateCellularStatusResponse { TelemetryResult telemetry_result = 1; } +message SetRateNicInfoResponse { + TelemetryResult telemetry_result = 1; +} + message SetRateActuatorControlTargetRequest { double rate_hz = 1; // The requested rate (in Hertz) } @@ -683,6 +702,17 @@ message CellularStatus { float arfcn = 18;//Absolute radio-frequency channel number } +// Network interface controller information. +message NicInfo { + uint32 instance_number = 1; + uint32 nic_id = 2; + string nic_model_name = 3; + uint64 imei = 4; //Unique NIC International Mobile Equipment Identity Number + uint64 iccid = 5; //Integrated Circuit Card Identification Number of SIM Card + uint64 imsi = 6; //Current SIM International mobile subscriber identity. + float firmware_version = 7;//The firmware version installed on the modem +} + // Status types. enum StatusTextType { STATUS_TEXT_TYPE_DEBUG = 0; // Debug diff --git a/protos/telemetry_server/telemetry_server.proto b/protos/telemetry_server/telemetry_server.proto index 6d2b5753b..2c7018639 100644 --- a/protos/telemetry_server/telemetry_server.proto +++ b/protos/telemetry_server/telemetry_server.proto @@ -26,6 +26,8 @@ service TelemetryServerService { rpc PublishBattery(PublishBatteryRequest) returns(PublishBatteryResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'cellular_status' updates. rpc PublishCellularStatus(PublishCellularStatusRequest) returns(PublishCellularStatusResponse) { option (mavsdk.options.async_type) = SYNC; } + // Publish to 'nic_info' updates. + rpc PublishNicInfo(PublishNicInfoRequest) returns(PublishNicInfoResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'status text' updates. rpc PublishStatusText(PublishStatusTextRequest) returns(PublishStatusTextResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'odometry' updates. @@ -89,6 +91,11 @@ message PublishCellularStatusRequest { CellularStatus cellular_status = 1; // The next Cellular status } +message PublishNicInfoRequest { + NicInfo nic_info = 1; // The next nic info +} + + message PublishRcStatusRequest { RcStatus rc_status = 1; // The next RC status } @@ -153,6 +160,10 @@ message PublishCellularStatusResponse { TelemetryServerResult telemetry_server_result = 1; } +message PublishNicInfoResponse { + TelemetryServerResult telemetry_server_result = 1; +} + message PublishStatusTextResponse { TelemetryServerResult telemetry_server_result = 1; } @@ -325,6 +336,17 @@ message CellularStatus { float arfcn = 18;//Absolute radio-frequency channel number } +// Network interface controller information. +message NicInfo { + uint32 instance_number = 1; + uint32 nic_id = 2; + string nic_model_name = 3; + uint64 imei = 4; //Unique NIC International Mobile Equipment Identity Number + uint64 iccid = 5; //Integrated Circuit Card Identification Number of SIM Card + uint64 imsi = 6; //Current SIM International mobile subscriber identity. + float firmware_version = 7;//The firmware version installed on the modem +} + // Status types. enum StatusTextType { STATUS_TEXT_TYPE_DEBUG = 0; // Debug From dcfd62c26afa88eb784d7811e537d5209b0eea43 Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Sat, 11 Feb 2023 19:23:18 -0500 Subject: [PATCH 6/8] update modem_info and cellular_status msgs --- protos/telemetry/telemetry.proto | 60 +++++++++---------- .../telemetry_server/telemetry_server.proto | 52 ++++++++-------- 2 files changed, 56 insertions(+), 56 deletions(-) diff --git a/protos/telemetry/telemetry.proto b/protos/telemetry/telemetry.proto index de66e7639..3e5c8d4bd 100644 --- a/protos/telemetry/telemetry.proto +++ b/protos/telemetry/telemetry.proto @@ -50,8 +50,8 @@ service TelemetryService { rpc SubscribeRcStatus(SubscribeRcStatusRequest) returns(stream RcStatusResponse) {} // Subscribe to 'Cellular status' updates. rpc SubscribeCellularStatus(SubscribeCellularStatusRequest) returns(stream CellularStatusResponse) {} - // Subscribe to 'NIC_INFO' updates. - rpc SubscribeNicInfo(SubscribeNicInfoRequest) returns(stream NicInfoResponse) {} + // Subscribe to 'MODEM_INFO' updates. + rpc SubscribeModemInfo(SubscribeModemInfoRequest) returns(stream ModemInfoResponse) {} // Subscribe to 'status text' updates. rpc SubscribeStatusText(SubscribeStatusTextRequest) returns(stream StatusTextResponse) {} // Subscribe to 'actuator control target' updates. @@ -111,8 +111,8 @@ service TelemetryService { rpc SetRateRcStatus(SetRateRcStatusRequest) returns(SetRateRcStatusResponse) {} // Set rate to 'Cellular status' updates. rpc SetRateCellularStatus(SetRateCellularStatusRequest) returns(SetRateCellularStatusResponse) {} - // Set rate to 'NIC_INFO' updates. - rpc SetRateNicInfo(SetRateNicInfoRequest) returns(SetRateNicInfoResponse) {} + // Set rate to 'MODEM_INFO' updates. + rpc SetRateModemInfo(SetRateModemInfoRequest) returns(SetRateModemInfoResponse) {} // Set rate to 'actuator control target' updates. rpc SetRateActuatorControlTarget(SetRateActuatorControlTargetRequest) returns(SetRateActuatorControlTargetResponse) {} // Set rate to 'actuator output status' updates. @@ -239,9 +239,9 @@ message CellularStatusResponse { CellularStatus cellular_status = 1; // The next cellular status } -message SubscribeNicInfoRequest {} -message NicInfoResponse { - NicInfo nic_info = 1; // The next nic info +message SubscribeModemInfoRequest {} +message ModemInfoResponse { + ModemInfo modem_info = 1; // The next modem info } @@ -428,7 +428,7 @@ message SetRateCellularStatusRequest { double rate_hz = 1; // The requested rate (in Hertz) } -message SetRateNicInfoRequest { +message SetRateModemInfoRequest { double rate_hz = 1; // The requested rate (in Hertz) } @@ -441,7 +441,7 @@ message SetRateCellularStatusResponse { TelemetryResult telemetry_result = 1; } -message SetRateNicInfoResponse { +message SetRateModemInfoResponse { TelemetryResult telemetry_result = 1; } @@ -689,28 +689,28 @@ message CellularStatus { uint32 mcc = 5; uint32 mnc = 6; uint32 lac = 7; - uint32 instance_number = 8; - uint64 download_rate = 9; - uint64 upload_rate = 10; - uint64 bit_error_rate = 11; - float rx_level = 12; - float tx_level = 13; - float signal_to_noise = 14; - string cell_tower_id = 15; - uint32 band_number = 16; - float band_frequency = 17; - float arfcn = 18;//Absolute radio-frequency channel number -} - -// Network interface controller information. -message NicInfo { + uint32 band_number = 8; + float band_frequency = 9; + uint32 channel_number = 10; + float rx_level = 11; + float tx_level = 12; + float rx_quality = 13; + uint32 link_tx_rate = 14; + uint32 link_rx_rate = 15; + uint32 bit_error_rate = 16; + uint32 instance_number = 17; + string cell_tower_id = 18; +} + +// Modem information. +message ModemInfo { uint32 instance_number = 1; - uint32 nic_id = 2; - string nic_model_name = 3; - uint64 imei = 4; //Unique NIC International Mobile Equipment Identity Number - uint64 iccid = 5; //Integrated Circuit Card Identification Number of SIM Card - uint64 imsi = 6; //Current SIM International mobile subscriber identity. - float firmware_version = 7;//The firmware version installed on the modem + uint64 imei = 2; //Unique Modem International Mobile Equipment Identity Number + uint64 iccid = 3; //Integrated Circuit Card Identification Number of SIM Card + uint64 imsi = 4; //Current SIM International mobile subscriber identity. + string modem_id = 5; + string firmware_version = 6; //The firmware version installed on the modem + string modem_model_name = 7; } // Status types. diff --git a/protos/telemetry_server/telemetry_server.proto b/protos/telemetry_server/telemetry_server.proto index 2c7018639..e908d5611 100644 --- a/protos/telemetry_server/telemetry_server.proto +++ b/protos/telemetry_server/telemetry_server.proto @@ -26,8 +26,8 @@ service TelemetryServerService { rpc PublishBattery(PublishBatteryRequest) returns(PublishBatteryResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'cellular_status' updates. rpc PublishCellularStatus(PublishCellularStatusRequest) returns(PublishCellularStatusResponse) { option (mavsdk.options.async_type) = SYNC; } - // Publish to 'nic_info' updates. - rpc PublishNicInfo(PublishNicInfoRequest) returns(PublishNicInfoResponse) { option (mavsdk.options.async_type) = SYNC; } + // Publish to 'modem_info' updates. + rpc PublishModemInfo(PublishModemInfoRequest) returns(PublishModemInfoResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'status text' updates. rpc PublishStatusText(PublishStatusTextRequest) returns(PublishStatusTextResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'odometry' updates. @@ -91,8 +91,8 @@ message PublishCellularStatusRequest { CellularStatus cellular_status = 1; // The next Cellular status } -message PublishNicInfoRequest { - NicInfo nic_info = 1; // The next nic info +message PublishModemInfoRequest { + ModemInfo modem_info = 1; // The next modem info } @@ -160,7 +160,7 @@ message PublishCellularStatusResponse { TelemetryServerResult telemetry_server_result = 1; } -message PublishNicInfoResponse { +message PublishModemInfoResponse { TelemetryServerResult telemetry_server_result = 1; } @@ -323,28 +323,28 @@ message CellularStatus { uint32 mcc = 5; uint32 mnc = 6; uint32 lac = 7; - uint32 instance_number = 8; - uint64 download_rate = 9; - uint64 upload_rate = 10; - uint64 bit_error_rate = 11; - float rx_level = 12; - float tx_level = 13; - float signal_to_noise = 14; - string cell_tower_id = 15; - uint32 band_number = 16; - float band_frequency = 17; - float arfcn = 18;//Absolute radio-frequency channel number -} - -// Network interface controller information. -message NicInfo { + uint32 band_number = 8; + float band_frequency = 9; + uint32 channel_number = 10; + float rx_level = 11; + float tx_level = 12; + float rx_quality = 13; + uint32 link_tx_rate = 14; + uint32 link_rx_rate = 15; + uint32 bit_error_rate = 16; + uint32 instance_number = 17; + string cell_tower_id = 18; +} + +// Modem information. +message ModemInfo { uint32 instance_number = 1; - uint32 nic_id = 2; - string nic_model_name = 3; - uint64 imei = 4; //Unique NIC International Mobile Equipment Identity Number - uint64 iccid = 5; //Integrated Circuit Card Identification Number of SIM Card - uint64 imsi = 6; //Current SIM International mobile subscriber identity. - float firmware_version = 7;//The firmware version installed on the modem + uint64 imei = 2; //Unique Modem International Mobile Equipment Identity Number + uint64 iccid = 3; //Integrated Circuit Card Identification Number of SIM Card + uint64 imsi = 4; //Current SIM International mobile subscriber identity. + string modem_id = 5; + string firmware_version = 6; //The firmware version installed on the modem + string modem_model_name = 7; } // Status types. From f5305d3d716c05806101103f74831069895d9777 Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Mon, 13 Feb 2023 18:46:50 -0500 Subject: [PATCH 7/8] change iccid to string --- protos/telemetry/telemetry.proto | 6 +++--- protos/telemetry_server/telemetry_server.proto | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/protos/telemetry/telemetry.proto b/protos/telemetry/telemetry.proto index 3e5c8d4bd..5daa58c6e 100644 --- a/protos/telemetry/telemetry.proto +++ b/protos/telemetry/telemetry.proto @@ -706,9 +706,9 @@ message CellularStatus { message ModemInfo { uint32 instance_number = 1; uint64 imei = 2; //Unique Modem International Mobile Equipment Identity Number - uint64 iccid = 3; //Integrated Circuit Card Identification Number of SIM Card - uint64 imsi = 4; //Current SIM International mobile subscriber identity. - string modem_id = 5; + uint64 imsi = 3; //Current SIM International mobile subscriber identity. + string modem_id = 4; + string iccid = 5; //Integrated Circuit Card Identification Number of SIM Card string firmware_version = 6; //The firmware version installed on the modem string modem_model_name = 7; } diff --git a/protos/telemetry_server/telemetry_server.proto b/protos/telemetry_server/telemetry_server.proto index e908d5611..44ddaa7a6 100644 --- a/protos/telemetry_server/telemetry_server.proto +++ b/protos/telemetry_server/telemetry_server.proto @@ -340,9 +340,9 @@ message CellularStatus { message ModemInfo { uint32 instance_number = 1; uint64 imei = 2; //Unique Modem International Mobile Equipment Identity Number - uint64 iccid = 3; //Integrated Circuit Card Identification Number of SIM Card - uint64 imsi = 4; //Current SIM International mobile subscriber identity. - string modem_id = 5; + uint64 imsi = 3; //Current SIM International mobile subscriber identity. + string modem_id = 4; + string iccid = 5; //Integrated Circuit Card Identification Number of SIM Card string firmware_version = 6; //The firmware version installed on the modem string modem_model_name = 7; } From e94f2bfa054acee3a811c10d5e95c0b0b6caa02c Mon Sep 17 00:00:00 2001 From: Mohamad Akkawi Date: Mon, 13 Feb 2023 23:37:26 -0500 Subject: [PATCH 8/8] add comp_info_basic and onboard_comp_status --- protos/telemetry/telemetry.proto | 65 +++++++++++++++++++ .../telemetry_server/telemetry_server.proto | 52 +++++++++++++++ 2 files changed, 117 insertions(+) diff --git a/protos/telemetry/telemetry.proto b/protos/telemetry/telemetry.proto index 5daa58c6e..cfca2c72e 100644 --- a/protos/telemetry/telemetry.proto +++ b/protos/telemetry/telemetry.proto @@ -52,6 +52,10 @@ service TelemetryService { rpc SubscribeCellularStatus(SubscribeCellularStatusRequest) returns(stream CellularStatusResponse) {} // Subscribe to 'MODEM_INFO' updates. rpc SubscribeModemInfo(SubscribeModemInfoRequest) returns(stream ModemInfoResponse) {} + // Subscribe to 'Onboard computer status' updates. + rpc SubscribeOnboardComputerStatus(SubscribeOnboardComputerStatusRequest) returns(stream OnboardComputerStatusResponse) {} + // Subscribe to 'Component info basic' updates. + rpc SubscribeComponentInfoBasic(SubscribeComponentInfoBasicRequest) returns(stream ComponentInfoBasicResponse) {} // Subscribe to 'status text' updates. rpc SubscribeStatusText(SubscribeStatusTextRequest) returns(stream StatusTextResponse) {} // Subscribe to 'actuator control target' updates. @@ -113,6 +117,10 @@ service TelemetryService { rpc SetRateCellularStatus(SetRateCellularStatusRequest) returns(SetRateCellularStatusResponse) {} // Set rate to 'MODEM_INFO' updates. rpc SetRateModemInfo(SetRateModemInfoRequest) returns(SetRateModemInfoResponse) {} + // Set rate to 'Onboard computer status' updates. + rpc SetRateOnboardComputerStatus(SetRateOnboardComputerStatusRequest) returns(SetRateOnboardComputerStatusResponse) {} + // Set rate to 'Component info basic' updates. + rpc SetRateComponentInfoBasic(SetRateComponentInfoBasicRequest) returns(SetRateComponentInfoBasicResponse) {} // Set rate to 'actuator control target' updates. rpc SetRateActuatorControlTarget(SetRateActuatorControlTargetRequest) returns(SetRateActuatorControlTargetResponse) {} // Set rate to 'actuator output status' updates. @@ -244,6 +252,15 @@ message ModemInfoResponse { ModemInfo modem_info = 1; // The next modem info } +message SubscribeOnboardComputerStatusRequest {} +message OnboardComputerStatusResponse { + OnboardComputerStatus onboard_computer_status = 1; // The next 'onboard computer status' +} + +message SubscribeComponentInfoBasicRequest {} +message ComponentInfoBasicResponse { + ComponentInfoBasic component_info_basic = 1; // The next 'component info basic' +} message SubscribeStatusTextRequest {} message StatusTextResponse { @@ -432,6 +449,13 @@ message SetRateModemInfoRequest { double rate_hz = 1; // The requested rate (in Hertz) } +message SetRateOnboardComputerStatusRequest { + double rate_hz = 1; // The requested rate (in Hertz) +} + +message SetRateComponentInfoBasicRequest { + double rate_hz = 1; // The requested rate (in Hertz) +} message SetRateRcStatusResponse { TelemetryResult telemetry_result = 1; @@ -445,6 +469,14 @@ message SetRateModemInfoResponse { TelemetryResult telemetry_result = 1; } +message SetRateOnboardComputerStatusResponse { + TelemetryResult telemetry_result = 1; +} + +message SetRateComponentInfoBasicResponse { + TelemetryResult telemetry_result = 1; +} + message SetRateActuatorControlTargetRequest { double rate_hz = 1; // The requested rate (in Hertz) } @@ -713,6 +745,39 @@ message ModemInfo { string modem_model_name = 7; } +message OnboardComputerStatus{ + uint64 time_usec = 1; + uint32 uptime = 2; + uint32 type = 3; + repeated uint32 cpu_cores = 4; + repeated uint32 cpu_combined = 5; + repeated uint32 gpu_cores = 6; + repeated uint32 gpu_combined = 7; + uint32 temperature_board = 8; + repeated uint32 temperature_core = 9; + repeated uint32 fan_speed = 10; + uint32 ram_usage = 11; + uint32 ram_total = 12; + repeated uint32 storage_type = 13; + repeated uint32 storage_usage = 14; + repeated uint32 storage_total = 15; + repeated uint32 link_type = 16; + repeated uint32 link_tx_rate = 17; + repeated uint32 link_rx_rate = 18; + repeated uint32 link_tx_max = 19; + repeated uint32 link_rx_max = 20; +} + +message ComponentInfoBasic { + uint32 time_boot_ms = 1; + uint64 capabilities = 2; + string vendor_name = 3; + string model_name = 4; + string software_version = 5; + string hardware_version = 6; + string serial_number = 7; +} + // Status types. enum StatusTextType { STATUS_TEXT_TYPE_DEBUG = 0; // Debug diff --git a/protos/telemetry_server/telemetry_server.proto b/protos/telemetry_server/telemetry_server.proto index 44ddaa7a6..44b5b3f7d 100644 --- a/protos/telemetry_server/telemetry_server.proto +++ b/protos/telemetry_server/telemetry_server.proto @@ -28,6 +28,10 @@ service TelemetryServerService { rpc PublishCellularStatus(PublishCellularStatusRequest) returns(PublishCellularStatusResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'modem_info' updates. rpc PublishModemInfo(PublishModemInfoRequest) returns(PublishModemInfoResponse) { option (mavsdk.options.async_type) = SYNC; } + // Publish to 'obc_status' updates. + rpc PublishOnboardComputerStatus(PublishOnboardComputerStatusRequest) returns(PublishOnboardComputerStatusResponse) { option (mavsdk.options.async_type) = SYNC; } + // Publish to 'component_info_basic' updates. + rpc PublishComponentInfoBasic(PublishComponentInfoBasicRequest) returns(PublishComponentInfoBasicResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'status text' updates. rpc PublishStatusText(PublishStatusTextRequest) returns(PublishStatusTextResponse) { option (mavsdk.options.async_type) = SYNC; } // Publish to 'odometry' updates. @@ -95,6 +99,13 @@ message PublishModemInfoRequest { ModemInfo modem_info = 1; // The next modem info } +message PublishOnboardComputerStatusRequest { + OnboardComputerStatus obc_status = 1; // The next OBC status +} + +message PublishComponentInfoBasicRequest { + ComponentInfoBasic component_info_basic = 1; // The next component info basic +} message PublishRcStatusRequest { RcStatus rc_status = 1; // The next RC status @@ -164,6 +175,14 @@ message PublishModemInfoResponse { TelemetryServerResult telemetry_server_result = 1; } +message PublishOnboardComputerStatusResponse { + TelemetryServerResult telemetry_server_result = 1; +} + +message PublishComponentInfoBasicResponse { + TelemetryServerResult telemetry_server_result = 1; +} + message PublishStatusTextResponse { TelemetryServerResult telemetry_server_result = 1; } @@ -347,6 +366,39 @@ message ModemInfo { string modem_model_name = 7; } +message OnboardComputerStatus{ + uint64 time_usec = 1; + uint32 uptime = 2; + uint32 type = 3; + repeated uint32 cpu_cores = 4; + repeated uint32 cpu_combined = 5; + repeated uint32 gpu_cores = 6; + repeated uint32 gpu_combined = 7; + uint32 temperature_board = 8; + repeated uint32 temperature_core = 9; + repeated uint32 fan_speed = 10; + uint32 ram_usage = 11; + uint32 ram_total = 12; + repeated uint32 storage_type = 13; + repeated uint32 storage_usage = 14; + repeated uint32 storage_total = 15; + repeated uint32 link_type = 16; + repeated uint32 link_tx_rate = 17; + repeated uint32 link_rx_rate = 18; + repeated uint32 link_tx_max = 19; + repeated uint32 link_rx_max = 20; +} + +message ComponentInfoBasic { + uint32 time_boot_ms = 1; + uint64 capabilities = 2; + string vendor_name = 3; + string model_name = 4; + string software_version = 5; + string hardware_version = 6; + string serial_number = 7; +} + // Status types. enum StatusTextType { STATUS_TEXT_TYPE_DEBUG = 0; // Debug