From f22dcdc177a7dbfa2597984933ef974e0a221875 Mon Sep 17 00:00:00 2001 From: Dominik <45536968+authaldo@users.noreply.github.com> Date: Sun, 27 Aug 2023 13:00:17 +0000 Subject: [PATCH] minor cleanup fixing warnings --- include/parameter_tree.hpp | 24 ++++++++++++------------ include/requests.hpp | 6 +++--- include/responses.hpp | 12 ++++++------ include/ros_parameter.hpp | 4 ++-- include/service_wrapper.hpp | 8 ++++---- src/service_wrapper.cpp | 17 ++++------------- 6 files changed, 31 insertions(+), 40 deletions(-) diff --git a/include/parameter_tree.hpp b/include/parameter_tree.hpp index 8008d27..6b7c529 100644 --- a/include/parameter_tree.hpp +++ b/include/parameter_tree.hpp @@ -19,17 +19,17 @@ * for the parameter tree. */ struct TreeElement { - TreeElement(const ROSParameter ¶meter, std::string fullParameterPath, - std::optional patternStart = std::nullopt, - std::optional patternEnd = std::nullopt) : - name(parameter.name), fullPath(std::move(fullParameterPath)), value(parameter.value), - searchPatternStart(patternStart), searchPatternEnd(patternEnd) {}; - - TreeElement(std::string name, std::string fullParameterPath, ROSParameterVariant value, - std::optional patternStart = std::nullopt, - std::optional patternEnd = std::nullopt) : - name(std::move(name)), fullPath(std::move(fullParameterPath)), value(std::move(value)), - searchPatternStart(patternStart), searchPatternEnd(patternEnd) {}; + TreeElement(const ROSParameter ¶meter_, std::string fullParameterPath_, + std::optional patternStart_ = std::nullopt, + std::optional patternEnd_ = std::nullopt) : + name(parameter_.name), fullPath(std::move(fullParameterPath_)), value(parameter_.value), + searchPatternStart(patternStart_), searchPatternEnd(patternEnd_) {}; + + TreeElement(std::string name_, std::string fullParameterPath_, ROSParameterVariant value_, + std::optional patternStart_ = std::nullopt, + std::optional patternEnd_ = std::nullopt) : + name(std::move(name_)), fullPath(std::move(fullParameterPath_)), value(std::move(value_)), + searchPatternStart(patternStart_), searchPatternEnd(patternEnd_) {}; std::string name; // parameter name without prefixes @@ -46,7 +46,7 @@ struct TreeElement { }; struct ParameterGroup { - explicit ParameterGroup(std::string prefix = "") : prefix(std::move(prefix)) {}; + explicit ParameterGroup(std::string prefix_ = "") : prefix(std::move(prefix_)) {}; std::string prefix; std::optional prefixSearchPatternStart; diff --git a/include/requests.hpp b/include/requests.hpp index 6cc988d..92f343c 100644 --- a/include/requests.hpp +++ b/include/requests.hpp @@ -19,7 +19,7 @@ struct Request { TERMINATE, QUERY_NODE_NAMES, QUERY_NODE_PARAMETERS, QUERY_PARAMETER_VALUES, MODIFY_PARAMETER_VALUE }; - explicit Request(Type type) : type(type) {}; + explicit Request(Type type_) : type(type_) {}; virtual ~Request() = default; Type type; @@ -28,13 +28,13 @@ struct Request { using RequestPtr = std::shared_ptr; struct ParameterValueRequest : Request { - explicit ParameterValueRequest(const std::vector ¶meterNames) : Request(Type::QUERY_PARAMETER_VALUES), parameterNames(parameterNames) {}; + explicit ParameterValueRequest(const std::vector ¶meterNames_) : Request(Type::QUERY_PARAMETER_VALUES), parameterNames(parameterNames_) {}; std::vector parameterNames; }; struct ParameterModificationRequest : Request { - ParameterModificationRequest(ROSParameter updatedParameter) : Request(Type::MODIFY_PARAMETER_VALUE), parameter(std::move(updatedParameter)) {}; + ParameterModificationRequest(ROSParameter updatedParameter_) : Request(Type::MODIFY_PARAMETER_VALUE), parameter(std::move(updatedParameter_)) {}; ROSParameter parameter; }; diff --git a/include/responses.hpp b/include/responses.hpp index d7ae06a..6dbcd02 100644 --- a/include/responses.hpp +++ b/include/responses.hpp @@ -18,7 +18,7 @@ struct Response { NODE_NAMES, PARAMETERS, MODIFICATION_RESULT, SERVICE_TIMEOUT }; - explicit Response(Type type) : type(type) {}; + explicit Response(Type type_) : type(type_) {}; virtual ~Response() = default; Type type; @@ -27,7 +27,7 @@ struct Response { using ResponsePtr = std::shared_ptr; struct NodeNameResponse : public Response { - explicit NodeNameResponse(const std::vector &nodeNames) : Response(Type::NODE_NAMES), nodeNames(nodeNames) {}; + explicit NodeNameResponse(const std::vector &nodeNames_) : Response(Type::NODE_NAMES), nodeNames(nodeNames_) {}; std::vector nodeNames; }; @@ -39,9 +39,9 @@ struct ParameterValueResponse : public Response { }; struct ParameterModificationResponse : public Response { - ParameterModificationResponse(std::string parameterName, bool success, std::string reason) : - Response(Type::MODIFICATION_RESULT), parameterName(std::move(parameterName)), success(success), - reason(std::move(reason)) {}; + ParameterModificationResponse(std::string parameterName_, bool success_, std::string reason_) : + Response(Type::MODIFICATION_RESULT), parameterName(std::move(parameterName_)), success(success_), + reason(std::move(reason_)) {}; std::string parameterName; bool success; @@ -49,7 +49,7 @@ struct ParameterModificationResponse : public Response { }; struct ServiceTimeout : public Response { - ServiceTimeout(std::string nodeName) : Response(Type::SERVICE_TIMEOUT), nodeName(std::move(nodeName)) {}; + explicit ServiceTimeout(std::string nodeName_) : Response(Type::SERVICE_TIMEOUT), nodeName(std::move(nodeName_)) {}; std::string nodeName; }; diff --git a/include/ros_parameter.hpp b/include/ros_parameter.hpp index 22a4e35..58d4b10 100644 --- a/include/ros_parameter.hpp +++ b/include/ros_parameter.hpp @@ -16,8 +16,8 @@ using ROSParameterVariant = std::variant; struct ROSParameter { - ROSParameter(std::string name, ROSParameterVariant value) : - name(std::move(name)), value(std::move(value)) {}; + ROSParameter(std::string name_, ROSParameterVariant value_) : + name(std::move(name_)), value(std::move(value_)) {}; std::string name; ROSParameterVariant value; diff --git a/include/service_wrapper.hpp b/include/service_wrapper.hpp index 389d2a3..30aa440 100644 --- a/include/service_wrapper.hpp +++ b/include/service_wrapper.hpp @@ -33,7 +33,7 @@ struct FutureTimeoutContainer { class ServiceWrapper { public: - explicit ServiceWrapper(bool ignoreDefaultParameters = true); + explicit ServiceWrapper(bool ignoreDefaultParameters_ = true); void terminate(); @@ -72,12 +72,12 @@ class ServiceWrapper { rclcpp::Client::SharedPtr setParametersClient; // callbacks for the results of the futures - void nodeParametersReceived(rclcpp::Client::SharedFuture future, + void nodeParametersReceived(const rclcpp::Client::SharedFuture &future, const std::shared_ptr &timeoutContainer); - void parameterValuesReceived(rclcpp::Client::SharedFuture future, + void parameterValuesReceived(const rclcpp::Client::SharedFuture &future, const std::vector ¶meterNames, const std::shared_ptr &timeoutContainer); - void parameterModificationResponseReceived(rclcpp::Client::SharedFuture future, + void parameterModificationResponseReceived(const rclcpp::Client::SharedFuture &future, const std::string ¶meterName, const std::shared_ptr &timeoutContainer); }; diff --git a/src/service_wrapper.cpp b/src/service_wrapper.cpp index 1b3163d..e8d6e42 100644 --- a/src/service_wrapper.cpp +++ b/src/service_wrapper.cpp @@ -13,16 +13,7 @@ using namespace std::chrono_literals; constexpr auto ROS_SERVICE_TIMEOUT = 1s; -template -bool checkServiceAvailability(T &serviceClient, std::chrono::seconds &timeout) { - if (!serviceClient->wait_for_service(timeout) || !rclcpp::ok()) { - return false; - } - - return true; -} - -ServiceWrapper::ServiceWrapper(bool ignoreDefaultParameters) : ignoreDefaultParameters(ignoreDefaultParameters) { +ServiceWrapper::ServiceWrapper(bool ignoreDefaultParameters_) : ignoreDefaultParameters(ignoreDefaultParameters_) { node = rclcpp::Node::make_shared("rig_reconfigure"); executor.add_node(node); @@ -204,7 +195,7 @@ void ServiceWrapper::handleRequest(const RequestPtr &request) { } } -void ServiceWrapper::nodeParametersReceived(rclcpp::Client::SharedFuture future, +void ServiceWrapper::nodeParametersReceived(const rclcpp::Client::SharedFuture &future, const std::shared_ptr &timeoutContainer) { auto valueRequest = std::make_shared(future.get()->result.names); @@ -220,7 +211,7 @@ void ServiceWrapper::nodeParametersReceived(rclcpp::Client::SharedFuture future, +void ServiceWrapper::parameterValuesReceived(const rclcpp::Client::SharedFuture &future, const std::vector ¶meterNames, const std::shared_ptr &timeoutContainer) { auto response = std::make_shared(); @@ -253,7 +244,7 @@ void ServiceWrapper::parameterValuesReceived(rclcpp::Client::SharedFuture future, +void ServiceWrapper::parameterModificationResponseReceived(const rclcpp::Client::SharedFuture &future, const std::string ¶meterName, const std::shared_ptr &timeoutContainer) { const auto &resultMsg = future.get();