diff --git a/include/moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp b/include/moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp index 5ceadcd..31c98b7 100644 --- a/include/moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp +++ b/include/moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp @@ -59,7 +59,7 @@ class ScenarioBasicServiceClient /** \brief Constructor * \param [in] node The ros node for sending request and wait response from server */ - ScenarioBasicServiceClient(rclcpp::Node::SharedPtr node); + ScenarioBasicServiceClient(const rclcpp::Node::SharedPtr& node); /** \brief the method to send the requests \e sending_request_number times * \param [in] sending_request_number the number for how many request is sent by client diff --git a/src/scenarios/scenario_basic_service_client.cpp b/src/scenarios/scenario_basic_service_client.cpp index ad677fe..5141b0c 100644 --- a/src/scenarios/scenario_basic_service_client.cpp +++ b/src/scenarios/scenario_basic_service_client.cpp @@ -46,7 +46,7 @@ namespace middleware_benchmark using namespace std::chrono_literals; -ScenarioBasicServiceClient::ScenarioBasicServiceClient(rclcpp::Node::SharedPtr node) : node_(node) +ScenarioBasicServiceClient::ScenarioBasicServiceClient(const rclcpp::Node::SharedPtr& node) : node_(node) { client_ = node_->create_client("add_two_ints");