Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add cellular_status and cellular_modem_info #309

Draft
wants to merge 8 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
70 changes: 70 additions & 0 deletions protos/telemetry/telemetry.proto
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,10 @@ 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 '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.
Expand Down Expand Up @@ -105,6 +109,10 @@ 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 '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.
Expand Down Expand Up @@ -226,6 +234,17 @@ message RcStatusResponse {
RcStatus rc_status = 1; // The next RC status
}

message SubscribeCellularStatusRequest {}
message CellularStatusResponse {
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'
Expand Down Expand Up @@ -404,10 +423,28 @@ 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 SetRateNicInfoRequest {
double rate_hz = 1; // The requested rate (in Hertz)
}


message SetRateRcStatusResponse {
TelemetryResult telemetry_result = 1;
}

message SetRateCellularStatusResponse {
TelemetryResult telemetry_result = 1;
}

message SetRateNicInfoResponse {
TelemetryResult telemetry_result = 1;
}

message SetRateActuatorControlTargetRequest {
double rate_hz = 1; // The requested rate (in Hertz)
}
Expand Down Expand Up @@ -643,6 +680,39 @@ 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 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
}

// 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
Expand Down
53 changes: 53 additions & 0 deletions protos/telemetry_server/telemetry_server.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,10 @@ 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 '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.
Expand Down Expand Up @@ -83,6 +87,15 @@ message PublishBatteryRequest {
Battery battery = 1; // The next 'battery' state
}

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
}
Expand Down Expand Up @@ -143,6 +156,13 @@ message PublishBatteryResponse {
TelemetryServerResult telemetry_server_result = 1;
}

message PublishCellularStatusResponse {
TelemetryServerResult telemetry_server_result = 1;
}

message PublishNicInfoResponse {
TelemetryServerResult telemetry_server_result = 1;
}

message PublishStatusTextResponse {
TelemetryServerResult telemetry_server_result = 1;
Expand Down Expand Up @@ -294,6 +314,39 @@ 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 status = 1;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

By the way, this is how I added status flags for the winch as a separate proto message: https://github.com/mavlink/MAVSDK-Proto/pull/308/files#diff-c29712674081664a7c33c32b2a4772848836bbbe76c1f1de17d5cb82b9f512acR73-R88

I.e. all bit flags from MAVLink became Booleans in Proto.

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
}

// 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
Expand Down