diff --git a/proto b/proto index 645ef7f919..6a70598087 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 645ef7f919f8e541b950ff5651edd681e926f953 +Subproject commit 6a70598087fa8fccda6ef7d89cc498550685659d diff --git a/src/integration_tests/action_goto.cpp b/src/integration_tests/action_goto.cpp index 0155aa2a33..a65551f104 100644 --- a/src/integration_tests/action_goto.cpp +++ b/src/integration_tests/action_goto.cpp @@ -47,12 +47,23 @@ TEST_F(SitlTest, PX4ActionGoto) action_ret = action->takeoff(); EXPECT_EQ(action_ret, Action::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); + std::this_thread::sleep_for(std::chrono::seconds(4)); // Go somewhere - action->goto_location(47.398000, 8.545592, NAN, NAN); - std::this_thread::sleep_for(std::chrono::seconds(10)); + action->goto_location(47.4, 8.545592, NAN, NAN); + std::this_thread::sleep_for(std::chrono::seconds(4)); + + LogInfo() << "Go slow for a bit."; + // Go slow for a bit + EXPECT_EQ(Action::Result::Success, action->set_current_speed(1.0f)); + std::this_thread::sleep_for(std::chrono::seconds(4)); + + LogInfo() << "Go fast again."; + // Then faster again + EXPECT_EQ(Action::Result::Success, action->set_current_speed(5.0f)); + std::this_thread::sleep_for(std::chrono::seconds(4)); + LogInfo() << "Go back."; // And back action->goto_location(47.3977233, 8.545592, NAN, NAN); std::this_thread::sleep_for(std::chrono::seconds(10)); diff --git a/src/mavsdk/plugins/action/action.cpp b/src/mavsdk/plugins/action/action.cpp index 36d0bb3e2a..0cdcfe8c23 100644 --- a/src/mavsdk/plugins/action/action.cpp +++ b/src/mavsdk/plugins/action/action.cpp @@ -256,6 +256,16 @@ Action::Result Action::set_return_to_launch_altitude(float relative_altitude_m) return _impl->set_return_to_launch_altitude(relative_altitude_m); } +void Action::set_current_speed_async(float speed_m_s, const ResultCallback callback) +{ + _impl->set_current_speed_async(speed_m_s, callback); +} + +Action::Result Action::set_current_speed(float speed_m_s) const +{ + return _impl->set_current_speed(speed_m_s); +} + std::ostream& operator<<(std::ostream& str, Action::Result const& result) { switch (result) { diff --git a/src/mavsdk/plugins/action/action_impl.cpp b/src/mavsdk/plugins/action/action_impl.cpp index 825343753a..735f1f564b 100644 --- a/src/mavsdk/plugins/action/action_impl.cpp +++ b/src/mavsdk/plugins/action/action_impl.cpp @@ -687,6 +687,33 @@ std::pair ActionImpl::get_return_to_launch_altitude() con result.second); } +void ActionImpl::set_current_speed_async(float speed_m_s, const Action::ResultCallback& callback) +{ + MavlinkCommandSender::CommandLong command{}; + + command.command = MAV_CMD_DO_CHANGE_SPEED; + command.params.maybe_param1 = 1.0f; // ground speed + command.params.maybe_param2 = speed_m_s; + command.params.maybe_param3 = -1.0f; // no throttle set + command.params.maybe_param4 = 0.0f; // reserved + command.target_component_id = _parent->get_autopilot_id(); + + _parent->send_command_async( + command, [this, callback](MavlinkCommandSender::Result result, float) { + command_result_callback(result, callback); + }); +} + +Action::Result ActionImpl::set_current_speed(float speed_m_s) +{ + auto prom = std::promise(); + auto fut = prom.get_future(); + + set_current_speed_async(speed_m_s, [&prom](Action::Result result) { prom.set_value(result); }); + + return fut.get(); +} + Action::Result ActionImpl::action_result_from_command_result(MavlinkCommandSender::Result result) { switch (result) { diff --git a/src/mavsdk/plugins/action/action_impl.h b/src/mavsdk/plugins/action/action_impl.h index 13ea243dc3..537f099962 100644 --- a/src/mavsdk/plugins/action/action_impl.h +++ b/src/mavsdk/plugins/action/action_impl.h @@ -94,6 +94,9 @@ class ActionImpl : public PluginImplBase { void get_return_to_launch_altitude_async( const Action::GetReturnToLaunchAltitudeCallback& callback) const; + void set_current_speed_async(float speed_m_s, const Action::ResultCallback& callback); + Action::Result set_current_speed(float speed_m_s); + Action::Result set_return_to_launch_altitude(const float relative_altitude_m) const; std::pair get_return_to_launch_altitude() const; diff --git a/src/mavsdk/plugins/action/include/plugins/action/action.h b/src/mavsdk/plugins/action/include/plugins/action/action.h index 55fc8276ba..a929586a41 100644 --- a/src/mavsdk/plugins/action/include/plugins/action/action.h +++ b/src/mavsdk/plugins/action/include/plugins/action/action.h @@ -587,6 +587,28 @@ class Action : public PluginBase { */ Result set_return_to_launch_altitude(float relative_altitude_m) const; + /** + * @brief Set current speed. + * + * This will set the speed during a mission, reposition, and similar. + * It is ephemeral, so not stored on the drone and does not survive a reboot. + * + * This function is non-blocking. See 'set_current_speed' for the blocking counterpart. + */ + void set_current_speed_async(float speed_m_s, const ResultCallback callback); + + /** + * @brief Set current speed. + * + * This will set the speed during a mission, reposition, and similar. + * It is ephemeral, so not stored on the drone and does not survive a reboot. + * + * This function is blocking. See 'set_current_speed_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result set_current_speed(float speed_m_s) const; + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/action/mocks/action_mock.h b/src/mavsdk/plugins/action/mocks/action_mock.h index 1b6152a99e..1308341d52 100644 --- a/src/mavsdk/plugins/action/mocks/action_mock.h +++ b/src/mavsdk/plugins/action/mocks/action_mock.h @@ -32,6 +32,7 @@ class MockAction { MOCK_CONST_METHOD1(set_maximum_speed, Action::Result(float)){}; MOCK_CONST_METHOD0(get_return_to_launch_altitude, std::pair()){}; MOCK_CONST_METHOD1(set_return_to_launch_altitude, Action::Result(float)){}; + MOCK_CONST_METHOD1(set_current_speed, Action::Result(float)){}; }; } // namespace testing diff --git a/src/mavsdk_server/src/generated/action/action.grpc.pb.cc b/src/mavsdk_server/src/generated/action/action.grpc.pb.cc index 12a6ae6d76..68168cd7ad 100644 --- a/src/mavsdk_server/src/generated/action/action.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/action/action.grpc.pb.cc @@ -45,6 +45,7 @@ static const char* ActionService_method_names[] = { "/mavsdk.rpc.action.ActionService/SetMaximumSpeed", "/mavsdk.rpc.action.ActionService/GetReturnToLaunchAltitude", "/mavsdk.rpc.action.ActionService/SetReturnToLaunchAltitude", + "/mavsdk.rpc.action.ActionService/SetCurrentSpeed", }; std::unique_ptr< ActionService::Stub> ActionService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -75,6 +76,7 @@ ActionService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& chan , rpcmethod_SetMaximumSpeed_(ActionService_method_names[18], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_GetReturnToLaunchAltitude_(ActionService_method_names[19], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SetReturnToLaunchAltitude_(ActionService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetCurrentSpeed_(ActionService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status ActionService::Stub::Arm(::grpc::ClientContext* context, const ::mavsdk::rpc::action::ArmRequest& request, ::mavsdk::rpc::action::ArmResponse* response) { @@ -560,6 +562,29 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetReturnToLaunchAltit return result; } +::grpc::Status ActionService::Stub::SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::mavsdk::rpc::action::SetCurrentSpeedResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetCurrentSpeed_, context, request, response); +} + +void ActionService::Stub::async::SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::mavsdk::rpc::action::SetCurrentSpeedResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetCurrentSpeed_, context, request, response, std::move(f)); +} + +void ActionService::Stub::async::SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetCurrentSpeed_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetCurrentSpeedResponse>* ActionService::Stub::PrepareAsyncSetCurrentSpeedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::action::SetCurrentSpeedResponse, ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetCurrentSpeed_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetCurrentSpeedResponse>* ActionService::Stub::AsyncSetCurrentSpeedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncSetCurrentSpeedRaw(context, request, cq); + result->StartCall(); + return result; +} + ActionService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( ActionService_method_names[0], @@ -771,6 +796,16 @@ ActionService::Service::Service() { ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse* resp) { return service->SetReturnToLaunchAltitude(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + ActionService_method_names[21], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< ActionService::Service, ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::mavsdk::rpc::action::SetCurrentSpeedResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](ActionService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::action::SetCurrentSpeedRequest* req, + ::mavsdk::rpc::action::SetCurrentSpeedResponse* resp) { + return service->SetCurrentSpeed(ctx, req, resp); + }, this))); } ActionService::Service::~Service() { @@ -923,6 +958,13 @@ ::grpc::Status ActionService::Service::SetReturnToLaunchAltitude(::grpc::ServerC return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status ActionService::Service::SetCurrentSpeed(::grpc::ServerContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/action/action.grpc.pb.h b/src/mavsdk_server/src/generated/action/action.grpc.pb.h index f2e3450020..c2bc476f55 100644 --- a/src/mavsdk_server/src/generated/action/action.grpc.pb.h +++ b/src/mavsdk_server/src/generated/action/action.grpc.pb.h @@ -276,6 +276,18 @@ class ActionService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>> PrepareAsyncSetReturnToLaunchAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>>(PrepareAsyncSetReturnToLaunchAltitudeRaw(context, request, cq)); } + // + // Set current speed. + // + // This will set the speed during a mission, reposition, and similar. + // It is ephemeral, so not stored on the drone and does not survive a reboot. + virtual ::grpc::Status SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetCurrentSpeedResponse>> AsyncSetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetCurrentSpeedResponse>>(AsyncSetCurrentSpeedRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetCurrentSpeedResponse>> PrepareAsyncSetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetCurrentSpeedResponse>>(PrepareAsyncSetCurrentSpeedRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -412,6 +424,13 @@ class ActionService final { // Set the return to launch minimum return altitude (in meters). virtual void SetReturnToLaunchAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest* request, ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse* response, std::function) = 0; virtual void SetReturnToLaunchAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest* request, ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Set current speed. + // + // This will set the speed during a mission, reposition, and similar. + // It is ephemeral, so not stored on the drone and does not survive a reboot. + virtual void SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response, std::function) = 0; + virtual void SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -459,6 +478,8 @@ class ActionService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::GetReturnToLaunchAltitudeResponse>* PrepareAsyncGetReturnToLaunchAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::GetReturnToLaunchAltitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>* AsyncSetReturnToLaunchAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>* PrepareAsyncSetReturnToLaunchAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetCurrentSpeedResponse>* AsyncSetCurrentSpeedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::action::SetCurrentSpeedResponse>* PrepareAsyncSetCurrentSpeedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -610,6 +631,13 @@ class ActionService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>> PrepareAsyncSetReturnToLaunchAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>>(PrepareAsyncSetReturnToLaunchAltitudeRaw(context, request, cq)); } + ::grpc::Status SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetCurrentSpeedResponse>> AsyncSetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetCurrentSpeedResponse>>(AsyncSetCurrentSpeedRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetCurrentSpeedResponse>> PrepareAsyncSetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetCurrentSpeedResponse>>(PrepareAsyncSetCurrentSpeedRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -655,6 +683,8 @@ class ActionService final { void GetReturnToLaunchAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::action::GetReturnToLaunchAltitudeRequest* request, ::mavsdk::rpc::action::GetReturnToLaunchAltitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetReturnToLaunchAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest* request, ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse* response, std::function) override; void SetReturnToLaunchAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest* request, ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response, std::function) override; + void SetCurrentSpeed(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -708,6 +738,8 @@ class ActionService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::GetReturnToLaunchAltitudeResponse>* PrepareAsyncGetReturnToLaunchAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::GetReturnToLaunchAltitudeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>* AsyncSetReturnToLaunchAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>* PrepareAsyncSetReturnToLaunchAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetCurrentSpeedResponse>* AsyncSetCurrentSpeedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::action::SetCurrentSpeedResponse>* PrepareAsyncSetCurrentSpeedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_Arm_; const ::grpc::internal::RpcMethod rpcmethod_Disarm_; const ::grpc::internal::RpcMethod rpcmethod_Takeoff_; @@ -729,6 +761,7 @@ class ActionService final { const ::grpc::internal::RpcMethod rpcmethod_SetMaximumSpeed_; const ::grpc::internal::RpcMethod rpcmethod_GetReturnToLaunchAltitude_; const ::grpc::internal::RpcMethod rpcmethod_SetReturnToLaunchAltitude_; + const ::grpc::internal::RpcMethod rpcmethod_SetCurrentSpeed_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -848,6 +881,12 @@ class ActionService final { // // Set the return to launch minimum return altitude (in meters). virtual ::grpc::Status SetReturnToLaunchAltitude(::grpc::ServerContext* context, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest* request, ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse* response); + // + // Set current speed. + // + // This will set the speed during a mission, reposition, and similar. + // It is ephemeral, so not stored on the drone and does not survive a reboot. + virtual ::grpc::Status SetCurrentSpeed(::grpc::ServerContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response); }; template class WithAsyncMethod_Arm : public BaseClass { @@ -1269,7 +1308,27 @@ class ActionService final { ::grpc::Service::RequestAsyncUnary(20, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_Arm > > > > > > > > > > > > > > > > > > > > AsyncService; + template + class WithAsyncMethod_SetCurrentSpeed : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SetCurrentSpeed() { + ::grpc::Service::MarkMethodAsync(21); + } + ~WithAsyncMethod_SetCurrentSpeed() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetCurrentSpeed(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* /*request*/, ::mavsdk::rpc::action::SetCurrentSpeedResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetCurrentSpeed(::grpc::ServerContext* context, ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::action::SetCurrentSpeedResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_Arm > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_Arm : public BaseClass { private: @@ -1837,7 +1896,34 @@ class ActionService final { virtual ::grpc::ServerUnaryReactor* SetReturnToLaunchAltitude( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest* /*request*/, ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_Arm > > > > > > > > > > > > > > > > > > > > CallbackService; + template + class WithCallbackMethod_SetCurrentSpeed : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SetCurrentSpeed() { + ::grpc::Service::MarkMethodCallback(21, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::mavsdk::rpc::action::SetCurrentSpeedResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* request, ::mavsdk::rpc::action::SetCurrentSpeedResponse* response) { return this->SetCurrentSpeed(context, request, response); }));} + void SetMessageAllocatorFor_SetCurrentSpeed( + ::grpc::MessageAllocator< ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::mavsdk::rpc::action::SetCurrentSpeedResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(21); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::mavsdk::rpc::action::SetCurrentSpeedResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_SetCurrentSpeed() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetCurrentSpeed(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* /*request*/, ::mavsdk::rpc::action::SetCurrentSpeedResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetCurrentSpeed( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* /*request*/, ::mavsdk::rpc::action::SetCurrentSpeedResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_Arm > > > > > > > > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_Arm : public BaseClass { @@ -2197,6 +2283,23 @@ class ActionService final { } }; template + class WithGenericMethod_SetCurrentSpeed : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetCurrentSpeed() { + ::grpc::Service::MarkMethodGeneric(21); + } + ~WithGenericMethod_SetCurrentSpeed() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetCurrentSpeed(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* /*request*/, ::mavsdk::rpc::action::SetCurrentSpeedResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_Arm : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2617,6 +2720,26 @@ class ActionService final { } }; template + class WithRawMethod_SetCurrentSpeed : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetCurrentSpeed() { + ::grpc::Service::MarkMethodRaw(21); + } + ~WithRawMethod_SetCurrentSpeed() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetCurrentSpeed(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* /*request*/, ::mavsdk::rpc::action::SetCurrentSpeedResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetCurrentSpeed(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_Arm : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -3079,6 +3202,28 @@ class ActionService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_SetCurrentSpeed : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetCurrentSpeed() { + ::grpc::Service::MarkMethodRawCallback(21, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetCurrentSpeed(context, request, response); })); + } + ~WithRawCallbackMethod_SetCurrentSpeed() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetCurrentSpeed(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* /*request*/, ::mavsdk::rpc::action::SetCurrentSpeedResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetCurrentSpeed( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_Arm : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -3645,9 +3790,36 @@ class ActionService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedSetReturnToLaunchAltitude(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest,::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_Arm > > > > > > > > > > > > > > > > > > > > StreamedUnaryService; + template + class WithStreamedUnaryMethod_SetCurrentSpeed : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_SetCurrentSpeed() { + ::grpc::Service::MarkMethodStreamed(21, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::mavsdk::rpc::action::SetCurrentSpeedResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::action::SetCurrentSpeedRequest, ::mavsdk::rpc::action::SetCurrentSpeedResponse>* streamer) { + return this->StreamedSetCurrentSpeed(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_SetCurrentSpeed() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SetCurrentSpeed(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::action::SetCurrentSpeedRequest* /*request*/, ::mavsdk::rpc::action::SetCurrentSpeedResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedSetCurrentSpeed(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::action::SetCurrentSpeedRequest,::mavsdk::rpc::action::SetCurrentSpeedResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_Arm > > > > > > > > > > > > > > > > > > > > > StreamedUnaryService; typedef Service SplitStreamedService; - typedef WithStreamedUnaryMethod_Arm > > > > > > > > > > > > > > > > > > > > StreamedService; + typedef WithStreamedUnaryMethod_Arm > > > > > > > > > > > > > > > > > > > > > StreamedService; }; } // namespace action diff --git a/src/mavsdk_server/src/generated/action/action.pb.cc b/src/mavsdk_server/src/generated/action/action.pb.cc index d3c1fbf1e5..58b28f741d 100644 --- a/src/mavsdk_server/src/generated/action/action.pb.cc +++ b/src/mavsdk_server/src/generated/action/action.pb.cc @@ -521,6 +521,30 @@ struct SetReturnToLaunchAltitudeResponseDefaultTypeInternal { }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT SetReturnToLaunchAltitudeResponseDefaultTypeInternal _SetReturnToLaunchAltitudeResponse_default_instance_; +constexpr SetCurrentSpeedRequest::SetCurrentSpeedRequest( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : speed_m_s_(0){} +struct SetCurrentSpeedRequestDefaultTypeInternal { + constexpr SetCurrentSpeedRequestDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~SetCurrentSpeedRequestDefaultTypeInternal() {} + union { + SetCurrentSpeedRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT SetCurrentSpeedRequestDefaultTypeInternal _SetCurrentSpeedRequest_default_instance_; +constexpr SetCurrentSpeedResponse::SetCurrentSpeedResponse( + ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) + : action_result_(nullptr){} +struct SetCurrentSpeedResponseDefaultTypeInternal { + constexpr SetCurrentSpeedResponseDefaultTypeInternal() + : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} + ~SetCurrentSpeedResponseDefaultTypeInternal() {} + union { + SetCurrentSpeedResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT SetCurrentSpeedResponseDefaultTypeInternal _SetCurrentSpeedResponse_default_instance_; constexpr ActionResult::ActionResult( ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) : result_str_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) @@ -538,7 +562,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT ActionResultDefaultTypeInternal } // namespace action } // namespace rpc } // namespace mavsdk -static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_action_2faction_2eproto[43]; +static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_action_2faction_2eproto[45]; static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_action_2faction_2eproto[2]; static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_action_2faction_2eproto = nullptr; @@ -793,6 +817,18 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_action_2faction_2eproto::offse ~0u, // no _weak_field_map_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse, action_result_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::action::SetCurrentSpeedRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::action::SetCurrentSpeedRequest, speed_m_s_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::action::SetCurrentSpeedResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::action::SetCurrentSpeedResponse, action_result_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::action::ActionResult, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -843,7 +879,9 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB { 230, -1, sizeof(::mavsdk::rpc::action::GetReturnToLaunchAltitudeResponse)}, { 237, -1, sizeof(::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest)}, { 243, -1, sizeof(::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse)}, - { 249, -1, sizeof(::mavsdk::rpc::action::ActionResult)}, + { 249, -1, sizeof(::mavsdk::rpc::action::SetCurrentSpeedRequest)}, + { 255, -1, sizeof(::mavsdk::rpc::action::SetCurrentSpeedResponse)}, + { 261, -1, sizeof(::mavsdk::rpc::action::ActionResult)}, }; static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = { @@ -889,6 +927,8 @@ static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = reinterpret_cast(&::mavsdk::rpc::action::_GetReturnToLaunchAltitudeResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::action::_SetReturnToLaunchAltitudeRequest_default_instance_), reinterpret_cast(&::mavsdk::rpc::action::_SetReturnToLaunchAltitudeResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::action::_SetCurrentSpeedRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::action::_SetCurrentSpeedResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::action::_ActionResult_default_instance_), }; @@ -959,87 +999,93 @@ const char descriptor_table_protodef_action_2faction_2eproto[] PROTOBUF_SECTION_ "\n SetReturnToLaunchAltitudeRequest\022\033\n\023re" "lative_altitude_m\030\001 \001(\002\"[\n!SetReturnToLa" "unchAltitudeResponse\0226\n\raction_result\030\001 " - "\001(\0132\037.mavsdk.rpc.action.ActionResult\"\335\003\n" - "\014ActionResult\0226\n\006result\030\001 \001(\0162&.mavsdk.r" - "pc.action.ActionResult.Result\022\022\n\nresult_" - "str\030\002 \001(\t\"\200\003\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000" - "\022\022\n\016RESULT_SUCCESS\020\001\022\024\n\020RESULT_NO_SYSTEM" - "\020\002\022\033\n\027RESULT_CONNECTION_ERROR\020\003\022\017\n\013RESUL" - "T_BUSY\020\004\022\031\n\025RESULT_COMMAND_DENIED\020\005\022.\n*R" - "ESULT_COMMAND_DENIED_LANDED_STATE_UNKNOW" - "N\020\006\022$\n RESULT_COMMAND_DENIED_NOT_LANDED\020" - "\007\022\022\n\016RESULT_TIMEOUT\020\010\022*\n&RESULT_VTOL_TRA" - "NSITION_SUPPORT_UNKNOWN\020\t\022%\n!RESULT_NO_V" - "TOL_TRANSITION_SUPPORT\020\n\022\032\n\026RESULT_PARAM" - "ETER_ERROR\020\013\022\026\n\022RESULT_UNSUPPORTED\020\014*\363\001\n" - "\020OrbitYawBehavior\0222\n.ORBIT_YAW_BEHAVIOR_" - "HOLD_FRONT_TO_CIRCLE_CENTER\020\000\022+\n\'ORBIT_Y" - "AW_BEHAVIOR_HOLD_INITIAL_HEADING\020\001\022#\n\037OR" - "BIT_YAW_BEHAVIOR_UNCONTROLLED\020\002\0223\n/ORBIT" - "_YAW_BEHAVIOR_HOLD_FRONT_TANGENT_TO_CIRC" - "LE\020\003\022$\n ORBIT_YAW_BEHAVIOR_RC_CONTROLLED" - "\020\0042\272\020\n\rActionService\022F\n\003Arm\022\035.mavsdk.rpc" - ".action.ArmRequest\032\036.mavsdk.rpc.action.A" - "rmResponse\"\000\022O\n\006Disarm\022 .mavsdk.rpc.acti" - "on.DisarmRequest\032!.mavsdk.rpc.action.Dis" - "armResponse\"\000\022R\n\007Takeoff\022!.mavsdk.rpc.ac" - "tion.TakeoffRequest\032\".mavsdk.rpc.action." - "TakeoffResponse\"\000\022I\n\004Land\022\036.mavsdk.rpc.a" - "ction.LandRequest\032\037.mavsdk.rpc.action.La" - "ndResponse\"\000\022O\n\006Reboot\022 .mavsdk.rpc.acti" - "on.RebootRequest\032!.mavsdk.rpc.action.Reb" - "ootResponse\"\000\022U\n\010Shutdown\022\".mavsdk.rpc.a" - "ction.ShutdownRequest\032#.mavsdk.rpc.actio" - "n.ShutdownResponse\"\000\022X\n\tTerminate\022#.mavs" - "dk.rpc.action.TerminateRequest\032$.mavsdk." - "rpc.action.TerminateResponse\"\000\022I\n\004Kill\022\036" - ".mavsdk.rpc.action.KillRequest\032\037.mavsdk." - "rpc.action.KillResponse\"\000\022g\n\016ReturnToLau" - "nch\022(.mavsdk.rpc.action.ReturnToLaunchRe" - "quest\032).mavsdk.rpc.action.ReturnToLaunch" - "Response\"\000\022a\n\014GotoLocation\022&.mavsdk.rpc." - "action.GotoLocationRequest\032\'.mavsdk.rpc." - "action.GotoLocationResponse\"\000\022R\n\007DoOrbit" - "\022!.mavsdk.rpc.action.DoOrbitRequest\032\".ma" - "vsdk.rpc.action.DoOrbitResponse\"\000\022I\n\004Hol" - "d\022\036.mavsdk.rpc.action.HoldRequest\032\037.mavs" - "dk.rpc.action.HoldResponse\"\000\022^\n\013SetActua" - "tor\022%.mavsdk.rpc.action.SetActuatorReque" - "st\032&.mavsdk.rpc.action.SetActuatorRespon" - "se\"\000\022|\n\025TransitionToFixedwing\022/.mavsdk.r" - "pc.action.TransitionToFixedwingRequest\0320" - ".mavsdk.rpc.action.TransitionToFixedwing" - "Response\"\000\022\202\001\n\027TransitionToMulticopter\0221" - ".mavsdk.rpc.action.TransitionToMulticopt" - "erRequest\0322.mavsdk.rpc.action.Transition" - "ToMulticopterResponse\"\000\022s\n\022GetTakeoffAlt" - "itude\022,.mavsdk.rpc.action.GetTakeoffAlti" - "tudeRequest\032-.mavsdk.rpc.action.GetTakeo" - "ffAltitudeResponse\"\000\022s\n\022SetTakeoffAltitu" - "de\022,.mavsdk.rpc.action.SetTakeoffAltitud" - "eRequest\032-.mavsdk.rpc.action.SetTakeoffA" - "ltitudeResponse\"\000\022j\n\017GetMaximumSpeed\022).m" - "avsdk.rpc.action.GetMaximumSpeedRequest\032" - "*.mavsdk.rpc.action.GetMaximumSpeedRespo" - "nse\"\000\022j\n\017SetMaximumSpeed\022).mavsdk.rpc.ac" - "tion.SetMaximumSpeedRequest\032*.mavsdk.rpc" - ".action.SetMaximumSpeedResponse\"\000\022\210\001\n\031Ge" - "tReturnToLaunchAltitude\0223.mavsdk.rpc.act" - "ion.GetReturnToLaunchAltitudeRequest\0324.m" - "avsdk.rpc.action.GetReturnToLaunchAltitu" - "deResponse\"\000\022\210\001\n\031SetReturnToLaunchAltitu" - "de\0223.mavsdk.rpc.action.SetReturnToLaunch" - "AltitudeRequest\0324.mavsdk.rpc.action.SetR" - "eturnToLaunchAltitudeResponse\"\000B\037\n\020io.ma" - "vsdk.actionB\013ActionProtob\006proto3" + "\001(\0132\037.mavsdk.rpc.action.ActionResult\"+\n\026" + "SetCurrentSpeedRequest\022\021\n\tspeed_m_s\030\001 \001(" + "\002\"Q\n\027SetCurrentSpeedResponse\0226\n\raction_r" + "esult\030\001 \001(\0132\037.mavsdk.rpc.action.ActionRe" + "sult\"\335\003\n\014ActionResult\0226\n\006result\030\001 \001(\0162&." + "mavsdk.rpc.action.ActionResult.Result\022\022\n" + "\nresult_str\030\002 \001(\t\"\200\003\n\006Result\022\022\n\016RESULT_U" + "NKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\024\n\020RESULT_N" + "O_SYSTEM\020\002\022\033\n\027RESULT_CONNECTION_ERROR\020\003\022" + "\017\n\013RESULT_BUSY\020\004\022\031\n\025RESULT_COMMAND_DENIE" + "D\020\005\022.\n*RESULT_COMMAND_DENIED_LANDED_STAT" + "E_UNKNOWN\020\006\022$\n RESULT_COMMAND_DENIED_NOT" + "_LANDED\020\007\022\022\n\016RESULT_TIMEOUT\020\010\022*\n&RESULT_" + "VTOL_TRANSITION_SUPPORT_UNKNOWN\020\t\022%\n!RES" + "ULT_NO_VTOL_TRANSITION_SUPPORT\020\n\022\032\n\026RESU" + "LT_PARAMETER_ERROR\020\013\022\026\n\022RESULT_UNSUPPORT" + "ED\020\014*\363\001\n\020OrbitYawBehavior\0222\n.ORBIT_YAW_B" + "EHAVIOR_HOLD_FRONT_TO_CIRCLE_CENTER\020\000\022+\n" + "\'ORBIT_YAW_BEHAVIOR_HOLD_INITIAL_HEADING" + "\020\001\022#\n\037ORBIT_YAW_BEHAVIOR_UNCONTROLLED\020\002\022" + "3\n/ORBIT_YAW_BEHAVIOR_HOLD_FRONT_TANGENT" + "_TO_CIRCLE\020\003\022$\n ORBIT_YAW_BEHAVIOR_RC_CO" + "NTROLLED\020\0042\246\021\n\rActionService\022F\n\003Arm\022\035.ma" + "vsdk.rpc.action.ArmRequest\032\036.mavsdk.rpc." + "action.ArmResponse\"\000\022O\n\006Disarm\022 .mavsdk." + "rpc.action.DisarmRequest\032!.mavsdk.rpc.ac" + "tion.DisarmResponse\"\000\022R\n\007Takeoff\022!.mavsd" + "k.rpc.action.TakeoffRequest\032\".mavsdk.rpc" + ".action.TakeoffResponse\"\000\022I\n\004Land\022\036.mavs" + "dk.rpc.action.LandRequest\032\037.mavsdk.rpc.a" + "ction.LandResponse\"\000\022O\n\006Reboot\022 .mavsdk." + "rpc.action.RebootRequest\032!.mavsdk.rpc.ac" + "tion.RebootResponse\"\000\022U\n\010Shutdown\022\".mavs" + "dk.rpc.action.ShutdownRequest\032#.mavsdk.r" + "pc.action.ShutdownResponse\"\000\022X\n\tTerminat" + "e\022#.mavsdk.rpc.action.TerminateRequest\032$" + ".mavsdk.rpc.action.TerminateResponse\"\000\022I" + "\n\004Kill\022\036.mavsdk.rpc.action.KillRequest\032\037" + ".mavsdk.rpc.action.KillResponse\"\000\022g\n\016Ret" + "urnToLaunch\022(.mavsdk.rpc.action.ReturnTo" + "LaunchRequest\032).mavsdk.rpc.action.Return" + "ToLaunchResponse\"\000\022a\n\014GotoLocation\022&.mav" + "sdk.rpc.action.GotoLocationRequest\032\'.mav" + "sdk.rpc.action.GotoLocationResponse\"\000\022R\n" + "\007DoOrbit\022!.mavsdk.rpc.action.DoOrbitRequ" + "est\032\".mavsdk.rpc.action.DoOrbitResponse\"" + "\000\022I\n\004Hold\022\036.mavsdk.rpc.action.HoldReques" + "t\032\037.mavsdk.rpc.action.HoldResponse\"\000\022^\n\013" + "SetActuator\022%.mavsdk.rpc.action.SetActua" + "torRequest\032&.mavsdk.rpc.action.SetActuat" + "orResponse\"\000\022|\n\025TransitionToFixedwing\022/." + "mavsdk.rpc.action.TransitionToFixedwingR" + "equest\0320.mavsdk.rpc.action.TransitionToF" + "ixedwingResponse\"\000\022\202\001\n\027TransitionToMulti" + "copter\0221.mavsdk.rpc.action.TransitionToM" + "ulticopterRequest\0322.mavsdk.rpc.action.Tr" + "ansitionToMulticopterResponse\"\000\022s\n\022GetTa" + "keoffAltitude\022,.mavsdk.rpc.action.GetTak" + "eoffAltitudeRequest\032-.mavsdk.rpc.action." + "GetTakeoffAltitudeResponse\"\000\022s\n\022SetTakeo" + "ffAltitude\022,.mavsdk.rpc.action.SetTakeof" + "fAltitudeRequest\032-.mavsdk.rpc.action.Set" + "TakeoffAltitudeResponse\"\000\022j\n\017GetMaximumS" + "peed\022).mavsdk.rpc.action.GetMaximumSpeed" + "Request\032*.mavsdk.rpc.action.GetMaximumSp" + "eedResponse\"\000\022j\n\017SetMaximumSpeed\022).mavsd" + "k.rpc.action.SetMaximumSpeedRequest\032*.ma" + "vsdk.rpc.action.SetMaximumSpeedResponse\"" + "\000\022\210\001\n\031GetReturnToLaunchAltitude\0223.mavsdk" + ".rpc.action.GetReturnToLaunchAltitudeReq" + "uest\0324.mavsdk.rpc.action.GetReturnToLaun" + "chAltitudeResponse\"\000\022\210\001\n\031SetReturnToLaun" + "chAltitude\0223.mavsdk.rpc.action.SetReturn" + "ToLaunchAltitudeRequest\0324.mavsdk.rpc.act" + "ion.SetReturnToLaunchAltitudeResponse\"\000\022" + "j\n\017SetCurrentSpeed\022).mavsdk.rpc.action.S" + "etCurrentSpeedRequest\032*.mavsdk.rpc.actio" + "n.SetCurrentSpeedResponse\"\000B\037\n\020io.mavsdk" + ".actionB\013ActionProtob\006proto3" ; static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_action_2faction_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, }; static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_action_2faction_2eproto_once; const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_action_2faction_2eproto = { - false, false, 5552, descriptor_table_protodef_action_2faction_2eproto, "action/action.proto", - &descriptor_table_action_2faction_2eproto_once, descriptor_table_action_2faction_2eproto_deps, 1, 43, + false, false, 5788, descriptor_table_protodef_action_2faction_2eproto, "action/action.proto", + &descriptor_table_action_2faction_2eproto_once, descriptor_table_action_2faction_2eproto_deps, 1, 45, schemas, file_default_instances, TableStruct_action_2faction_2eproto::offsets, file_level_metadata_action_2faction_2eproto, file_level_enum_descriptors_action_2faction_2eproto, file_level_service_descriptors_action_2faction_2eproto, }; @@ -9031,6 +9077,389 @@ ::PROTOBUF_NAMESPACE_ID::Metadata SetReturnToLaunchAltitudeResponse::GetMetadata // =================================================================== +class SetCurrentSpeedRequest::_Internal { + public: +}; + +SetCurrentSpeedRequest::SetCurrentSpeedRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.action.SetCurrentSpeedRequest) +} +SetCurrentSpeedRequest::SetCurrentSpeedRequest(const SetCurrentSpeedRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + speed_m_s_ = from.speed_m_s_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.action.SetCurrentSpeedRequest) +} + +inline void SetCurrentSpeedRequest::SharedCtor() { +speed_m_s_ = 0; +} + +SetCurrentSpeedRequest::~SetCurrentSpeedRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.action.SetCurrentSpeedRequest) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void SetCurrentSpeedRequest::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); +} + +void SetCurrentSpeedRequest::ArenaDtor(void* object) { + SetCurrentSpeedRequest* _this = reinterpret_cast< SetCurrentSpeedRequest* >(object); + (void)_this; +} +void SetCurrentSpeedRequest::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void SetCurrentSpeedRequest::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SetCurrentSpeedRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.action.SetCurrentSpeedRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + speed_m_s_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetCurrentSpeedRequest::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // float speed_m_s = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 13)) { + speed_m_s_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* SetCurrentSpeedRequest::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.action.SetCurrentSpeedRequest) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float speed_m_s = 1; + if (!(this->_internal_speed_m_s() <= 0 && this->_internal_speed_m_s() >= 0)) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_speed_m_s(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.action.SetCurrentSpeedRequest) + return target; +} + +size_t SetCurrentSpeedRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.action.SetCurrentSpeedRequest) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float speed_m_s = 1; + if (!(this->_internal_speed_m_s() <= 0 && this->_internal_speed_m_s() >= 0)) { + total_size += 1 + 4; + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetCurrentSpeedRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SetCurrentSpeedRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetCurrentSpeedRequest::GetClassData() const { return &_class_data_; } + +void SetCurrentSpeedRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SetCurrentSpeedRequest::MergeFrom(const SetCurrentSpeedRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.action.SetCurrentSpeedRequest) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (!(from._internal_speed_m_s() <= 0 && from._internal_speed_m_s() >= 0)) { + _internal_set_speed_m_s(from._internal_speed_m_s()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetCurrentSpeedRequest::CopyFrom(const SetCurrentSpeedRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.action.SetCurrentSpeedRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetCurrentSpeedRequest::IsInitialized() const { + return true; +} + +void SetCurrentSpeedRequest::InternalSwap(SetCurrentSpeedRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(speed_m_s_, other->speed_m_s_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetCurrentSpeedRequest::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_action_2faction_2eproto_getter, &descriptor_table_action_2faction_2eproto_once, + file_level_metadata_action_2faction_2eproto[42]); +} + +// =================================================================== + +class SetCurrentSpeedResponse::_Internal { + public: + static const ::mavsdk::rpc::action::ActionResult& action_result(const SetCurrentSpeedResponse* msg); +}; + +const ::mavsdk::rpc::action::ActionResult& +SetCurrentSpeedResponse::_Internal::action_result(const SetCurrentSpeedResponse* msg) { + return *msg->action_result_; +} +SetCurrentSpeedResponse::SetCurrentSpeedResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + if (!is_message_owned) { + RegisterArenaDtor(arena); + } + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.action.SetCurrentSpeedResponse) +} +SetCurrentSpeedResponse::SetCurrentSpeedResponse(const SetCurrentSpeedResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_action_result()) { + action_result_ = new ::mavsdk::rpc::action::ActionResult(*from.action_result_); + } else { + action_result_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.action.SetCurrentSpeedResponse) +} + +inline void SetCurrentSpeedResponse::SharedCtor() { +action_result_ = nullptr; +} + +SetCurrentSpeedResponse::~SetCurrentSpeedResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.action.SetCurrentSpeedResponse) + if (GetArenaForAllocation() != nullptr) return; + SharedDtor(); + _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +inline void SetCurrentSpeedResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete action_result_; +} + +void SetCurrentSpeedResponse::ArenaDtor(void* object) { + SetCurrentSpeedResponse* _this = reinterpret_cast< SetCurrentSpeedResponse* >(object); + (void)_this; +} +void SetCurrentSpeedResponse::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) { +} +void SetCurrentSpeedResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SetCurrentSpeedResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.action.SetCurrentSpeedResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && action_result_ != nullptr) { + delete action_result_; + } + action_result_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetCurrentSpeedResponse::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::PROTOBUF_NAMESPACE_ID::uint32 tag; + ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.action.ActionResult action_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_action_result(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + default: { + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto success; + } + ptr = UnknownFieldParse(tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + continue; + } + } // switch + } // while +success: + return ptr; +failure: + ptr = nullptr; + goto success; +#undef CHK_ +} + +::PROTOBUF_NAMESPACE_ID::uint8* SetCurrentSpeedResponse::_InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.action.SetCurrentSpeedResponse) + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.action.ActionResult action_result = 1; + if (this->_internal_has_action_result()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 1, _Internal::action_result(this), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.action.SetCurrentSpeedResponse) + return target; +} + +size_t SetCurrentSpeedResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.action.SetCurrentSpeedResponse) + size_t total_size = 0; + + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.action.ActionResult action_result = 1; + if (this->_internal_has_action_result()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *action_result_); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( + _internal_metadata_, total_size, &_cached_size_); + } + int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetCurrentSpeedResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SetCurrentSpeedResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetCurrentSpeedResponse::GetClassData() const { return &_class_data_; } + +void SetCurrentSpeedResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, + const ::PROTOBUF_NAMESPACE_ID::Message&from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SetCurrentSpeedResponse::MergeFrom(const SetCurrentSpeedResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.action.SetCurrentSpeedResponse) + GOOGLE_DCHECK_NE(&from, this); + ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_action_result()) { + _internal_mutable_action_result()->::mavsdk::rpc::action::ActionResult::MergeFrom(from._internal_action_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetCurrentSpeedResponse::CopyFrom(const SetCurrentSpeedResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.action.SetCurrentSpeedResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetCurrentSpeedResponse::IsInitialized() const { + return true; +} + +void SetCurrentSpeedResponse::InternalSwap(SetCurrentSpeedResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(action_result_, other->action_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetCurrentSpeedResponse::GetMetadata() const { + return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( + &descriptor_table_action_2faction_2eproto_getter, &descriptor_table_action_2faction_2eproto_once, + file_level_metadata_action_2faction_2eproto[43]); +} + +// =================================================================== + class ActionResult::_Internal { public: }; @@ -9254,7 +9683,7 @@ void ActionResult::InternalSwap(ActionResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata ActionResult::GetMetadata() const { return ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors( &descriptor_table_action_2faction_2eproto_getter, &descriptor_table_action_2faction_2eproto_once, - file_level_metadata_action_2faction_2eproto[42]); + file_level_metadata_action_2faction_2eproto[44]); } // @@protoc_insertion_point(namespace_scope) @@ -9388,6 +9817,12 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::action::SetReturnToLaunchAltitudeReq template<> PROTOBUF_NOINLINE ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::action::SetReturnToLaunchAltitudeResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::action::SetCurrentSpeedRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::action::SetCurrentSpeedRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::action::SetCurrentSpeedRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::action::SetCurrentSpeedResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::action::SetCurrentSpeedResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::action::SetCurrentSpeedResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::action::ActionResult* Arena::CreateMaybeMessage< ::mavsdk::rpc::action::ActionResult >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::action::ActionResult >(arena); } diff --git a/src/mavsdk_server/src/generated/action/action.pb.h b/src/mavsdk_server/src/generated/action/action.pb.h index 7681899b19..a1c732be78 100644 --- a/src/mavsdk_server/src/generated/action/action.pb.h +++ b/src/mavsdk_server/src/generated/action/action.pb.h @@ -48,7 +48,7 @@ struct TableStruct_action_2faction_2eproto { PROTOBUF_SECTION_VARIABLE(protodesc_cold); static const ::PROTOBUF_NAMESPACE_ID::internal::AuxiliaryParseTableField aux[] PROTOBUF_SECTION_VARIABLE(protodesc_cold); - static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[43] + static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[45] PROTOBUF_SECTION_VARIABLE(protodesc_cold); static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[]; static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[]; @@ -139,6 +139,12 @@ extern SetActuatorRequestDefaultTypeInternal _SetActuatorRequest_default_instanc class SetActuatorResponse; struct SetActuatorResponseDefaultTypeInternal; extern SetActuatorResponseDefaultTypeInternal _SetActuatorResponse_default_instance_; +class SetCurrentSpeedRequest; +struct SetCurrentSpeedRequestDefaultTypeInternal; +extern SetCurrentSpeedRequestDefaultTypeInternal _SetCurrentSpeedRequest_default_instance_; +class SetCurrentSpeedResponse; +struct SetCurrentSpeedResponseDefaultTypeInternal; +extern SetCurrentSpeedResponseDefaultTypeInternal _SetCurrentSpeedResponse_default_instance_; class SetMaximumSpeedRequest; struct SetMaximumSpeedRequestDefaultTypeInternal; extern SetMaximumSpeedRequestDefaultTypeInternal _SetMaximumSpeedRequest_default_instance_; @@ -218,6 +224,8 @@ template<> ::mavsdk::rpc::action::ReturnToLaunchRequest* Arena::CreateMaybeMessa template<> ::mavsdk::rpc::action::ReturnToLaunchResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::action::ReturnToLaunchResponse>(Arena*); template<> ::mavsdk::rpc::action::SetActuatorRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::action::SetActuatorRequest>(Arena*); template<> ::mavsdk::rpc::action::SetActuatorResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::action::SetActuatorResponse>(Arena*); +template<> ::mavsdk::rpc::action::SetCurrentSpeedRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::action::SetCurrentSpeedRequest>(Arena*); +template<> ::mavsdk::rpc::action::SetCurrentSpeedResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::action::SetCurrentSpeedResponse>(Arena*); template<> ::mavsdk::rpc::action::SetMaximumSpeedRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::action::SetMaximumSpeedRequest>(Arena*); template<> ::mavsdk::rpc::action::SetMaximumSpeedResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::action::SetMaximumSpeedResponse>(Arena*); template<> ::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::action::SetReturnToLaunchAltitudeRequest>(Arena*); @@ -6269,6 +6277,293 @@ class SetReturnToLaunchAltitudeResponse final : }; // ------------------------------------------------------------------- +class SetCurrentSpeedRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.action.SetCurrentSpeedRequest) */ { + public: + inline SetCurrentSpeedRequest() : SetCurrentSpeedRequest(nullptr) {} + ~SetCurrentSpeedRequest() override; + explicit constexpr SetCurrentSpeedRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetCurrentSpeedRequest(const SetCurrentSpeedRequest& from); + SetCurrentSpeedRequest(SetCurrentSpeedRequest&& from) noexcept + : SetCurrentSpeedRequest() { + *this = ::std::move(from); + } + + inline SetCurrentSpeedRequest& operator=(const SetCurrentSpeedRequest& from) { + CopyFrom(from); + return *this; + } + inline SetCurrentSpeedRequest& operator=(SetCurrentSpeedRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetCurrentSpeedRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetCurrentSpeedRequest* internal_default_instance() { + return reinterpret_cast( + &_SetCurrentSpeedRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 42; + + friend void swap(SetCurrentSpeedRequest& a, SetCurrentSpeedRequest& b) { + a.Swap(&b); + } + inline void Swap(SetCurrentSpeedRequest* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetCurrentSpeedRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline SetCurrentSpeedRequest* New() const final { + return new SetCurrentSpeedRequest(); + } + + SetCurrentSpeedRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetCurrentSpeedRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const SetCurrentSpeedRequest& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetCurrentSpeedRequest* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.action.SetCurrentSpeedRequest"; + } + protected: + explicit SetCurrentSpeedRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kSpeedMSFieldNumber = 1, + }; + // float speed_m_s = 1; + void clear_speed_m_s(); + float speed_m_s() const; + void set_speed_m_s(float value); + private: + float _internal_speed_m_s() const; + void _internal_set_speed_m_s(float value); + public: + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.action.SetCurrentSpeedRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + float speed_m_s_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_action_2faction_2eproto; +}; +// ------------------------------------------------------------------- + +class SetCurrentSpeedResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.action.SetCurrentSpeedResponse) */ { + public: + inline SetCurrentSpeedResponse() : SetCurrentSpeedResponse(nullptr) {} + ~SetCurrentSpeedResponse() override; + explicit constexpr SetCurrentSpeedResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetCurrentSpeedResponse(const SetCurrentSpeedResponse& from); + SetCurrentSpeedResponse(SetCurrentSpeedResponse&& from) noexcept + : SetCurrentSpeedResponse() { + *this = ::std::move(from); + } + + inline SetCurrentSpeedResponse& operator=(const SetCurrentSpeedResponse& from) { + CopyFrom(from); + return *this; + } + inline SetCurrentSpeedResponse& operator=(SetCurrentSpeedResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena()) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetCurrentSpeedResponse& default_instance() { + return *internal_default_instance(); + } + static inline const SetCurrentSpeedResponse* internal_default_instance() { + return reinterpret_cast( + &_SetCurrentSpeedResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 43; + + friend void swap(SetCurrentSpeedResponse& a, SetCurrentSpeedResponse& b) { + a.Swap(&b); + } + inline void Swap(SetCurrentSpeedResponse* other) { + if (other == this) return; + if (GetOwningArena() == other->GetOwningArena()) { + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetCurrentSpeedResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + inline SetCurrentSpeedResponse* New() const final { + return new SetCurrentSpeedResponse(); + } + + SetCurrentSpeedResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetCurrentSpeedResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const SetCurrentSpeedResponse& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message*to, const ::PROTOBUF_NAMESPACE_ID::Message&from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize( + ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetCurrentSpeedResponse* other); + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.action.SetCurrentSpeedResponse"; + } + protected: + explicit SetCurrentSpeedResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + private: + static void ArenaDtor(void* object); + inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kActionResultFieldNumber = 1, + }; + // .mavsdk.rpc.action.ActionResult action_result = 1; + bool has_action_result() const; + private: + bool _internal_has_action_result() const; + public: + void clear_action_result(); + const ::mavsdk::rpc::action::ActionResult& action_result() const; + PROTOBUF_MUST_USE_RESULT ::mavsdk::rpc::action::ActionResult* release_action_result(); + ::mavsdk::rpc::action::ActionResult* mutable_action_result(); + void set_allocated_action_result(::mavsdk::rpc::action::ActionResult* action_result); + private: + const ::mavsdk::rpc::action::ActionResult& _internal_action_result() const; + ::mavsdk::rpc::action::ActionResult* _internal_mutable_action_result(); + public: + void unsafe_arena_set_allocated_action_result( + ::mavsdk::rpc::action::ActionResult* action_result); + ::mavsdk::rpc::action::ActionResult* unsafe_arena_release_action_result(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.action.SetCurrentSpeedResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::action::ActionResult* action_result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_action_2faction_2eproto; +}; +// ------------------------------------------------------------------- + class ActionResult final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.action.ActionResult) */ { public: @@ -6313,7 +6608,7 @@ class ActionResult final : &_ActionResult_default_instance_); } static constexpr int kIndexInFileMessages = - 42; + 44; friend void swap(ActionResult& a, ActionResult& b) { a.Swap(&b); @@ -8901,6 +9196,124 @@ inline void SetReturnToLaunchAltitudeResponse::set_allocated_action_result(::mav // ------------------------------------------------------------------- +// SetCurrentSpeedRequest + +// float speed_m_s = 1; +inline void SetCurrentSpeedRequest::clear_speed_m_s() { + speed_m_s_ = 0; +} +inline float SetCurrentSpeedRequest::_internal_speed_m_s() const { + return speed_m_s_; +} +inline float SetCurrentSpeedRequest::speed_m_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.action.SetCurrentSpeedRequest.speed_m_s) + return _internal_speed_m_s(); +} +inline void SetCurrentSpeedRequest::_internal_set_speed_m_s(float value) { + + speed_m_s_ = value; +} +inline void SetCurrentSpeedRequest::set_speed_m_s(float value) { + _internal_set_speed_m_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.action.SetCurrentSpeedRequest.speed_m_s) +} + +// ------------------------------------------------------------------- + +// SetCurrentSpeedResponse + +// .mavsdk.rpc.action.ActionResult action_result = 1; +inline bool SetCurrentSpeedResponse::_internal_has_action_result() const { + return this != internal_default_instance() && action_result_ != nullptr; +} +inline bool SetCurrentSpeedResponse::has_action_result() const { + return _internal_has_action_result(); +} +inline void SetCurrentSpeedResponse::clear_action_result() { + if (GetArenaForAllocation() == nullptr && action_result_ != nullptr) { + delete action_result_; + } + action_result_ = nullptr; +} +inline const ::mavsdk::rpc::action::ActionResult& SetCurrentSpeedResponse::_internal_action_result() const { + const ::mavsdk::rpc::action::ActionResult* p = action_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::action::_ActionResult_default_instance_); +} +inline const ::mavsdk::rpc::action::ActionResult& SetCurrentSpeedResponse::action_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.action.SetCurrentSpeedResponse.action_result) + return _internal_action_result(); +} +inline void SetCurrentSpeedResponse::unsafe_arena_set_allocated_action_result( + ::mavsdk::rpc::action::ActionResult* action_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(action_result_); + } + action_result_ = action_result; + if (action_result) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.action.SetCurrentSpeedResponse.action_result) +} +inline ::mavsdk::rpc::action::ActionResult* SetCurrentSpeedResponse::release_action_result() { + + ::mavsdk::rpc::action::ActionResult* temp = action_result_; + action_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::action::ActionResult* SetCurrentSpeedResponse::unsafe_arena_release_action_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.action.SetCurrentSpeedResponse.action_result) + + ::mavsdk::rpc::action::ActionResult* temp = action_result_; + action_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::action::ActionResult* SetCurrentSpeedResponse::_internal_mutable_action_result() { + + if (action_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::action::ActionResult>(GetArenaForAllocation()); + action_result_ = p; + } + return action_result_; +} +inline ::mavsdk::rpc::action::ActionResult* SetCurrentSpeedResponse::mutable_action_result() { + ::mavsdk::rpc::action::ActionResult* _msg = _internal_mutable_action_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.action.SetCurrentSpeedResponse.action_result) + return _msg; +} +inline void SetCurrentSpeedResponse::set_allocated_action_result(::mavsdk::rpc::action::ActionResult* action_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete action_result_; + } + if (action_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::action::ActionResult>::GetOwningArena(action_result); + if (message_arena != submessage_arena) { + action_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, action_result, submessage_arena); + } + + } else { + + } + action_result_ = action_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.action.SetCurrentSpeedResponse.action_result) +} + +// ------------------------------------------------------------------- + // ActionResult // .mavsdk.rpc.action.ActionResult.Result result = 1; @@ -9056,6 +9469,10 @@ inline void ActionResult::set_allocated_result_str(std::string* result_str) { // ------------------------------------------------------------------- +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + // @@protoc_insertion_point(namespace_scope) diff --git a/src/mavsdk_server/src/plugins/action/action_service_impl.h b/src/mavsdk_server/src/plugins/action/action_service_impl.h index 19c60ecf4e..1af3f9bb36 100644 --- a/src/mavsdk_server/src/plugins/action/action_service_impl.h +++ b/src/mavsdk_server/src/plugins/action/action_service_impl.h @@ -682,6 +682,34 @@ class ActionServiceImpl final : public rpc::action::ActionService::Service { return grpc::Status::OK; } + grpc::Status SetCurrentSpeed( + grpc::ServerContext* /* context */, + const rpc::action::SetCurrentSpeedRequest* request, + rpc::action::SetCurrentSpeedResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::Action::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "SetCurrentSpeed sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->set_current_speed(request->speed_m_s()); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + void stop() { _stopped.store(true);