diff --git a/protos/param_server/param_server.proto b/protos/param_server/param_server.proto index b44c1d95..f5e4b3e6 100644 --- a/protos/param_server/param_server.proto +++ b/protos/param_server/param_server.proto @@ -9,6 +9,14 @@ option java_outer_classname = "ParamServerProto"; // Provide raw access to retrieve and provide server parameters. service ParamServerService { + /* + * Set param protocol. + * + * The extended param protocol is used by default. This allows to use the previous/normal one. + * + * Note that camera definition files are meant to implement/use the extended protocol. + */ + rpc SetProtocol(SetProtocolRequest) returns(SetProtocolResponse) { option (mavsdk.options.async_type) = SYNC; } /* * Retrieve an int parameter. * @@ -60,6 +68,13 @@ service ParamServerService { rpc SubscribeChangedParamCustom(SubscribeChangedParamCustomRequest) returns(stream ChangedParamCustomResponse) { option (mavsdk.options.async_type) = ASYNC; } } +message SetProtocolRequest { + bool extended_protocol = 1; // Use extended protocol +} +message SetProtocolResponse { + ParamServerResult param_server_result = 1; +} + message RetrieveParamIntRequest { string name = 1; // Name of the parameter }