From bc8c30b1f4aa476062dddf449a88ae7411c09d14 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 26 Apr 2024 11:29:55 +1200 Subject: [PATCH] Add log_streaming (#339) * Add log_streaming --- protos/log_streaming/log_streaming.proto | 56 ++++++++++++++++++++++++ 1 file changed, 56 insertions(+) create mode 100644 protos/log_streaming/log_streaming.proto diff --git a/protos/log_streaming/log_streaming.proto b/protos/log_streaming/log_streaming.proto new file mode 100644 index 00000000..350e081d --- /dev/null +++ b/protos/log_streaming/log_streaming.proto @@ -0,0 +1,56 @@ +syntax = "proto3"; + +package mavsdk.rpc.log_streaming; + +import "mavsdk_options.proto"; + +option java_package = "io.mavsdk.log_streaming"; +option java_outer_classname = "LogStreamingProto"; + +// Provide log streaming data. +service LogStreamingService { + // Start streaming logging data. + rpc StartLogStreaming(StartLogStreamingRequest) returns(StartLogStreamingResponse) {} + // Stop streaming logging data. + rpc StopLogStreaming(StopLogStreamingRequest) returns(StopLogStreamingResponse) {} + // Subscribe to logging messages + rpc SubscribeLogStreamingRaw(SubscribeLogStreamingRawRequest) returns(stream LogStreamingRawResponse) { option (mavsdk.options.async_type) = ASYNC; } +} + +message StartLogStreamingRequest {} +message StartLogStreamingResponse { + LogStreamingResult log_streaming_result = 1; +} + +message StopLogStreamingRequest {} +message StopLogStreamingResponse { + LogStreamingResult log_streaming_result = 1; +} + +message SubscribeLogStreamingRawRequest {} +message LogStreamingRawResponse { + LogStreamingRaw logging_raw = 1; // A message containing logged data +} + +// Raw logging data type +message LogStreamingRaw { + string data = 1; // Ulog file stream data encoded as base64 +} + +// Result type. +message LogStreamingResult { + // Possible results returned for logging requests + enum Result { + RESULT_SUCCESS = 0; // Request succeeded + RESULT_NO_SYSTEM = 1; // No system connected + RESULT_CONNECTION_ERROR = 2; // Connection error + RESULT_BUSY = 3; // System busy + RESULT_COMMAND_DENIED = 4; // Command denied + RESULT_TIMEOUT = 5; // Timeout + RESULT_UNSUPPORTED = 6; // Unsupported + RESULT_UNKNOWN = 7; // Unknown error + } + + Result result = 1; // Result enum value + string result_str = 2; // Human-readable English string describing the result +}