use forward slashes instead of double underscores (#364)
* use forward slashes instead of double underscores * define parameter service suffixes in commonly shared header * style * forgot list_parameters * correct license year
This commit is contained in:
		
							parent
							
								
									f175726b0e
								
							
						
					
					
						commit
						b1ed15ebc7
					
				
					 3 changed files with 48 additions and 11 deletions
				
			
		| 
						 | 
					@ -19,6 +19,8 @@
 | 
				
			||||||
#include <string>
 | 
					#include <string>
 | 
				
			||||||
#include <vector>
 | 
					#include <vector>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#include "./parameter_service_names.hpp"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
using rclcpp::parameter_client::AsyncParametersClient;
 | 
					using rclcpp::parameter_client::AsyncParametersClient;
 | 
				
			||||||
using rclcpp::parameter_client::SyncParametersClient;
 | 
					using rclcpp::parameter_client::SyncParametersClient;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
| 
						 | 
					@ -34,15 +36,15 @@ AsyncParametersClient::AsyncParametersClient(
 | 
				
			||||||
    remote_node_name_ = node_->get_name();
 | 
					    remote_node_name_ = node_->get_name();
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  get_parameters_client_ = node_->create_client<rcl_interfaces::srv::GetParameters>(
 | 
					  get_parameters_client_ = node_->create_client<rcl_interfaces::srv::GetParameters>(
 | 
				
			||||||
    remote_node_name_ + "__get_parameters", qos_profile);
 | 
					    remote_node_name_ + "/" + parameter_service_names::get_parameters, qos_profile);
 | 
				
			||||||
  get_parameter_types_client_ = node_->create_client<rcl_interfaces::srv::GetParameterTypes>(
 | 
					  get_parameter_types_client_ = node_->create_client<rcl_interfaces::srv::GetParameterTypes>(
 | 
				
			||||||
    remote_node_name_ + "__get_parameter_types", qos_profile);
 | 
					    remote_node_name_ + "/" + parameter_service_names::get_parameter_types, qos_profile);
 | 
				
			||||||
  set_parameters_client_ = node_->create_client<rcl_interfaces::srv::SetParameters>(
 | 
					  set_parameters_client_ = node_->create_client<rcl_interfaces::srv::SetParameters>(
 | 
				
			||||||
    remote_node_name_ + "__set_parameters", qos_profile);
 | 
					    remote_node_name_ + "/" + parameter_service_names::set_parameters, qos_profile);
 | 
				
			||||||
  list_parameters_client_ = node_->create_client<rcl_interfaces::srv::ListParameters>(
 | 
					  list_parameters_client_ = node_->create_client<rcl_interfaces::srv::ListParameters>(
 | 
				
			||||||
    remote_node_name_ + "__list_parameters", qos_profile);
 | 
					    remote_node_name_ + "/" + parameter_service_names::list_parameters, qos_profile);
 | 
				
			||||||
  describe_parameters_client_ = node_->create_client<rcl_interfaces::srv::DescribeParameters>(
 | 
					  describe_parameters_client_ = node_->create_client<rcl_interfaces::srv::DescribeParameters>(
 | 
				
			||||||
    remote_node_name_ + "__describe_parameters", qos_profile);
 | 
					    remote_node_name_ + "/" + parameter_service_names::describe_parameters, qos_profile);
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
 | 
					std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -19,6 +19,8 @@
 | 
				
			||||||
#include <string>
 | 
					#include <string>
 | 
				
			||||||
#include <vector>
 | 
					#include <vector>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#include "./parameter_service_names.hpp"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
using rclcpp::parameter_service::ParameterService;
 | 
					using rclcpp::parameter_service::ParameterService;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
ParameterService::ParameterService(
 | 
					ParameterService::ParameterService(
 | 
				
			||||||
| 
						 | 
					@ -29,7 +31,7 @@ ParameterService::ParameterService(
 | 
				
			||||||
  std::weak_ptr<rclcpp::node::Node> captured_node = node_;
 | 
					  std::weak_ptr<rclcpp::node::Node> captured_node = node_;
 | 
				
			||||||
  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
 | 
					  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
 | 
				
			||||||
  get_parameters_service_ = node_->create_service<rcl_interfaces::srv::GetParameters>(
 | 
					  get_parameters_service_ = node_->create_service<rcl_interfaces::srv::GetParameters>(
 | 
				
			||||||
    std::string(node_->get_name()) + "__get_parameters",
 | 
					    std::string(node_->get_name()) + "/" + parameter_service_names::get_parameters,
 | 
				
			||||||
    [captured_node](
 | 
					    [captured_node](
 | 
				
			||||||
      const std::shared_ptr<rmw_request_id_t>,
 | 
					      const std::shared_ptr<rmw_request_id_t>,
 | 
				
			||||||
      const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request,
 | 
					      const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request,
 | 
				
			||||||
| 
						 | 
					@ -48,7 +50,7 @@ ParameterService::ParameterService(
 | 
				
			||||||
  );
 | 
					  );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  get_parameter_types_service_ = node_->create_service<rcl_interfaces::srv::GetParameterTypes>(
 | 
					  get_parameter_types_service_ = node_->create_service<rcl_interfaces::srv::GetParameterTypes>(
 | 
				
			||||||
    std::string(node_->get_name()) + "__get_parameter_types",
 | 
					    std::string(node_->get_name()) + "/" + parameter_service_names::get_parameter_types,
 | 
				
			||||||
    [captured_node](
 | 
					    [captured_node](
 | 
				
			||||||
      const std::shared_ptr<rmw_request_id_t>,
 | 
					      const std::shared_ptr<rmw_request_id_t>,
 | 
				
			||||||
      const std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Request> request,
 | 
					      const std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Request> request,
 | 
				
			||||||
| 
						 | 
					@ -68,7 +70,7 @@ ParameterService::ParameterService(
 | 
				
			||||||
  );
 | 
					  );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  set_parameters_service_ = node_->create_service<rcl_interfaces::srv::SetParameters>(
 | 
					  set_parameters_service_ = node_->create_service<rcl_interfaces::srv::SetParameters>(
 | 
				
			||||||
    std::string(node_->get_name()) + "__set_parameters",
 | 
					    std::string(node_->get_name()) + "/" + parameter_service_names::set_parameters,
 | 
				
			||||||
    [captured_node](
 | 
					    [captured_node](
 | 
				
			||||||
      const std::shared_ptr<rmw_request_id_t>,
 | 
					      const std::shared_ptr<rmw_request_id_t>,
 | 
				
			||||||
      const std::shared_ptr<rcl_interfaces::srv::SetParameters::Request> request,
 | 
					      const std::shared_ptr<rcl_interfaces::srv::SetParameters::Request> request,
 | 
				
			||||||
| 
						 | 
					@ -90,7 +92,7 @@ ParameterService::ParameterService(
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  set_parameters_atomically_service_ =
 | 
					  set_parameters_atomically_service_ =
 | 
				
			||||||
    node_->create_service<rcl_interfaces::srv::SetParametersAtomically>(
 | 
					    node_->create_service<rcl_interfaces::srv::SetParametersAtomically>(
 | 
				
			||||||
    std::string(node_->get_name()) + "__set_parameters_atomically",
 | 
					    std::string(node_->get_name()) + "/" + parameter_service_names::set_parameters_atomically,
 | 
				
			||||||
    [captured_node](
 | 
					    [captured_node](
 | 
				
			||||||
      const std::shared_ptr<rmw_request_id_t>,
 | 
					      const std::shared_ptr<rmw_request_id_t>,
 | 
				
			||||||
      const std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Request> request,
 | 
					      const std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Request> request,
 | 
				
			||||||
| 
						 | 
					@ -114,7 +116,7 @@ ParameterService::ParameterService(
 | 
				
			||||||
  );
 | 
					  );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  describe_parameters_service_ = node_->create_service<rcl_interfaces::srv::DescribeParameters>(
 | 
					  describe_parameters_service_ = node_->create_service<rcl_interfaces::srv::DescribeParameters>(
 | 
				
			||||||
    std::string(node_->get_name()) + "__describe_parameters",
 | 
					    std::string(node_->get_name()) + "/" + parameter_service_names::describe_parameters,
 | 
				
			||||||
    [captured_node](
 | 
					    [captured_node](
 | 
				
			||||||
      const std::shared_ptr<rmw_request_id_t>,
 | 
					      const std::shared_ptr<rmw_request_id_t>,
 | 
				
			||||||
      const std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Request> request,
 | 
					      const std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Request> request,
 | 
				
			||||||
| 
						 | 
					@ -131,7 +133,7 @@ ParameterService::ParameterService(
 | 
				
			||||||
  );
 | 
					  );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  list_parameters_service_ = node_->create_service<rcl_interfaces::srv::ListParameters>(
 | 
					  list_parameters_service_ = node_->create_service<rcl_interfaces::srv::ListParameters>(
 | 
				
			||||||
    std::string(node_->get_name()) + "__list_parameters",
 | 
					    std::string(node_->get_name()) + "/" + parameter_service_names::list_parameters,
 | 
				
			||||||
    [captured_node](
 | 
					    [captured_node](
 | 
				
			||||||
      const std::shared_ptr<rmw_request_id_t>,
 | 
					      const std::shared_ptr<rmw_request_id_t>,
 | 
				
			||||||
      const std::shared_ptr<rcl_interfaces::srv::ListParameters::Request> request,
 | 
					      const std::shared_ptr<rcl_interfaces::srv::ListParameters::Request> request,
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
							
								
								
									
										33
									
								
								rclcpp/src/rclcpp/parameter_service_names.hpp
									
										
									
									
									
										Normal file
									
								
							
							
						
						
									
										33
									
								
								rclcpp/src/rclcpp/parameter_service_names.hpp
									
										
									
									
									
										Normal file
									
								
							| 
						 | 
					@ -0,0 +1,33 @@
 | 
				
			||||||
 | 
					// Copyright 2017 Open Source Robotics Foundation, Inc.
 | 
				
			||||||
 | 
					//
 | 
				
			||||||
 | 
					// Licensed under the Apache License, Version 2.0 (the "License");
 | 
				
			||||||
 | 
					// you may not use this file except in compliance with the License.
 | 
				
			||||||
 | 
					// You may obtain a copy of the License at
 | 
				
			||||||
 | 
					//
 | 
				
			||||||
 | 
					//     http://www.apache.org/licenses/LICENSE-2.0
 | 
				
			||||||
 | 
					//
 | 
				
			||||||
 | 
					// Unless required by applicable law or agreed to in writing, software
 | 
				
			||||||
 | 
					// distributed under the License is distributed on an "AS IS" BASIS,
 | 
				
			||||||
 | 
					// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 | 
				
			||||||
 | 
					// See the License for the specific language governing permissions and
 | 
				
			||||||
 | 
					// limitations under the License.
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#ifndef RCLCPP__PARAMETER_SERVICE_NAMES_HPP_
 | 
				
			||||||
 | 
					#define RCLCPP__PARAMETER_SERVICE_NAMES_HPP_
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					namespace rclcpp
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					namespace parameter_service_names
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					static constexpr const char * get_parameters = "get_parameters";
 | 
				
			||||||
 | 
					static constexpr const char * get_parameter_types = "get_parameter_types";
 | 
				
			||||||
 | 
					static constexpr const char * set_parameters = "set_parameters";
 | 
				
			||||||
 | 
					static constexpr const char * set_parameters_atomically = "set_parameters_atomically";
 | 
				
			||||||
 | 
					static constexpr const char * describe_parameters = "describe_parameters";
 | 
				
			||||||
 | 
					static constexpr const char * list_parameters = "list_parameters";
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					}  // namespace parameter_service_names
 | 
				
			||||||
 | 
					}  // namespace rclcpp
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#endif  // RCLCPP__PARAMETER_SERVICE_NAMES_HPP_
 | 
				
			||||||
		Loading…
	
	Add table
		Add a link
		
	
		Reference in a new issue