Skip to content

Commit

Permalink
minor cleanup fixing warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
authaldo committed Aug 27, 2023
1 parent 6839ea5 commit f22dcdc
Show file tree
Hide file tree
Showing 6 changed files with 31 additions and 40 deletions.
24 changes: 12 additions & 12 deletions include/parameter_tree.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,17 +19,17 @@
* for the parameter tree.
*/
struct TreeElement {
TreeElement(const ROSParameter &parameter, std::string fullParameterPath,
std::optional<std::size_t> patternStart = std::nullopt,
std::optional<std::size_t> 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<std::size_t> patternStart = std::nullopt,
std::optional<std::size_t> patternEnd = std::nullopt) :
name(std::move(name)), fullPath(std::move(fullParameterPath)), value(std::move(value)),
searchPatternStart(patternStart), searchPatternEnd(patternEnd) {};
TreeElement(const ROSParameter &parameter_, std::string fullParameterPath_,
std::optional<std::size_t> patternStart_ = std::nullopt,
std::optional<std::size_t> 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<std::size_t> patternStart_ = std::nullopt,
std::optional<std::size_t> 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

Expand All @@ -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<std::size_t> prefixSearchPatternStart;
Expand Down
6 changes: 3 additions & 3 deletions include/requests.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -28,13 +28,13 @@ struct Request {
using RequestPtr = std::shared_ptr<Request>;

struct ParameterValueRequest : Request {
explicit ParameterValueRequest(const std::vector<std::string> &parameterNames) : Request(Type::QUERY_PARAMETER_VALUES), parameterNames(parameterNames) {};
explicit ParameterValueRequest(const std::vector<std::string> &parameterNames_) : Request(Type::QUERY_PARAMETER_VALUES), parameterNames(parameterNames_) {};

std::vector<std::string> 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;
};
Expand Down
12 changes: 6 additions & 6 deletions include/responses.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -27,7 +27,7 @@ struct Response {
using ResponsePtr = std::shared_ptr<Response>;

struct NodeNameResponse : public Response {
explicit NodeNameResponse(const std::vector<std::string> &nodeNames) : Response(Type::NODE_NAMES), nodeNames(nodeNames) {};
explicit NodeNameResponse(const std::vector<std::string> &nodeNames_) : Response(Type::NODE_NAMES), nodeNames(nodeNames_) {};

std::vector<std::string> nodeNames;
};
Expand All @@ -39,17 +39,17 @@ 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;
std::string reason;
};

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;
};
Expand Down
4 changes: 2 additions & 2 deletions include/ros_parameter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
using ROSParameterVariant = std::variant<bool, int, double, std::string>;

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;
Expand Down
8 changes: 4 additions & 4 deletions include/service_wrapper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ struct FutureTimeoutContainer {

class ServiceWrapper {
public:
explicit ServiceWrapper(bool ignoreDefaultParameters = true);
explicit ServiceWrapper(bool ignoreDefaultParameters_ = true);

void terminate();

Expand Down Expand Up @@ -72,12 +72,12 @@ class ServiceWrapper {
rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedPtr setParametersClient;

// callbacks for the results of the futures
void nodeParametersReceived(rclcpp::Client<rcl_interfaces::srv::ListParameters>::SharedFuture future,
void nodeParametersReceived(const rclcpp::Client<rcl_interfaces::srv::ListParameters>::SharedFuture &future,
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer);
void parameterValuesReceived(rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedFuture future,
void parameterValuesReceived(const rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedFuture &future,
const std::vector<std::string> &parameterNames,
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer);
void parameterModificationResponseReceived(rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedFuture future,
void parameterModificationResponseReceived(const rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedFuture &future,
const std::string &parameterName,
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer);
};
Expand Down
17 changes: 4 additions & 13 deletions src/service_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,16 +13,7 @@ using namespace std::chrono_literals;

constexpr auto ROS_SERVICE_TIMEOUT = 1s;

template <typename T>
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);
Expand Down Expand Up @@ -204,7 +195,7 @@ void ServiceWrapper::handleRequest(const RequestPtr &request) {
}
}

void ServiceWrapper::nodeParametersReceived(rclcpp::Client<rcl_interfaces::srv::ListParameters>::SharedFuture future,
void ServiceWrapper::nodeParametersReceived(const rclcpp::Client<rcl_interfaces::srv::ListParameters>::SharedFuture &future,
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer) {
auto valueRequest = std::make_shared<ParameterValueRequest>(future.get()->result.names);

Expand All @@ -220,7 +211,7 @@ void ServiceWrapper::nodeParametersReceived(rclcpp::Client<rcl_interfaces::srv::
requestQueue.push(std::move(valueRequest));
}

void ServiceWrapper::parameterValuesReceived(rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedFuture future,
void ServiceWrapper::parameterValuesReceived(const rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedFuture &future,
const std::vector<std::string> &parameterNames,
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer) {
auto response = std::make_shared<ParameterValueResponse>();
Expand Down Expand Up @@ -253,7 +244,7 @@ void ServiceWrapper::parameterValuesReceived(rclcpp::Client<rcl_interfaces::srv:
responseQueue.push(response);
}

void ServiceWrapper::parameterModificationResponseReceived(rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedFuture future,
void ServiceWrapper::parameterModificationResponseReceived(const rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedFuture &future,
const std::string &parameterName,
const std::shared_ptr<FutureTimeoutContainer> &timeoutContainer) {
const auto &resultMsg = future.get();
Expand Down

0 comments on commit f22dcdc

Please sign in to comment.