.. _program_listing_file_include_rclcpp_parameter_client.hpp: Program Listing for File parameter_client.hpp ============================================= |exhale_lsh| :ref:`Return to documentation for file ` (``include/rclcpp/parameter_client.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2015 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_CLIENT_HPP_ #define RCLCPP__PARAMETER_CLIENT_HPP_ #include #include #include #include #include #include #include "rcl_interfaces/msg/parameter.hpp" #include "rcl_interfaces/msg/parameter_event.hpp" #include "rcl_interfaces/msg/parameter_value.hpp" #include "rcl_interfaces/srv/describe_parameters.hpp" #include "rcl_interfaces/srv/get_parameter_types.hpp" #include "rcl_interfaces/srv/get_parameters.hpp" #include "rcl_interfaces/srv/list_parameters.hpp" #include "rcl_interfaces/srv/set_parameters.hpp" #include "rcl_interfaces/srv/set_parameters_atomically.hpp" #include "rcl_yaml_param_parser/parser.h" #include "rclcpp/exceptions.hpp" #include "rclcpp/executors.hpp" #include "rclcpp/create_subscription.hpp" #include "rclcpp/macros.hpp" #include "rclcpp/node.hpp" #include "rclcpp/parameter.hpp" #include "rclcpp/parameter_map.hpp" #include "rclcpp/type_support_decl.hpp" #include "rclcpp/visibility_control.hpp" #include "rmw/rmw.h" namespace rclcpp { class AsyncParametersClient { public: RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient) RCLCPP_PUBLIC AsyncParametersClient( const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group = nullptr); template explicit AsyncParametersClient( const std::shared_ptr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group = nullptr) : AsyncParametersClient( node->get_node_base_interface(), node->get_node_topics_interface(), node->get_node_graph_interface(), node->get_node_services_interface(), remote_node_name, qos_profile, group) {} template explicit AsyncParametersClient( NodeT * node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group = nullptr) : AsyncParametersClient( node->get_node_base_interface(), node->get_node_topics_interface(), node->get_node_graph_interface(), node->get_node_services_interface(), remote_node_name, qos_profile, group) {} RCLCPP_PUBLIC std::shared_future> get_parameters( const std::vector & names, std::function< void(std::shared_future>) > callback = nullptr); RCLCPP_PUBLIC std::shared_future> describe_parameters( const std::vector & names, std::function< void(std::shared_future>) > callback = nullptr); RCLCPP_PUBLIC std::shared_future> get_parameter_types( const std::vector & names, std::function< void(std::shared_future>) > callback = nullptr); RCLCPP_PUBLIC std::shared_future> set_parameters( const std::vector & parameters, std::function< void(std::shared_future>) > callback = nullptr); RCLCPP_PUBLIC std::shared_future set_parameters_atomically( const std::vector & parameters, std::function< void(std::shared_future) > callback = nullptr); RCLCPP_PUBLIC std::shared_future> delete_parameters( const std::vector & parameters_names); RCLCPP_PUBLIC std::shared_future> load_parameters( const std::string & yaml_filename); RCLCPP_PUBLIC std::shared_future> load_parameters(const rclcpp::ParameterMap & parameter_map); RCLCPP_PUBLIC std::shared_future list_parameters( const std::vector & prefixes, uint64_t depth, std::function< void(std::shared_future) > callback = nullptr); template< typename CallbackT, typename AllocatorT = std::allocator> typename rclcpp::Subscription::SharedPtr on_parameter_event( CallbackT && callback, const rclcpp::QoS & qos = ( rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)) ), const rclcpp::SubscriptionOptionsWithAllocator & options = ( rclcpp::SubscriptionOptionsWithAllocator() )) { return this->on_parameter_event( this->node_topics_interface_, callback, qos, options); } template< typename CallbackT, typename NodeT, typename AllocatorT = std::allocator> static typename rclcpp::Subscription::SharedPtr on_parameter_event( NodeT && node, CallbackT && callback, const rclcpp::QoS & qos = ( rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)) ), const rclcpp::SubscriptionOptionsWithAllocator & options = ( rclcpp::SubscriptionOptionsWithAllocator() )) { return rclcpp::create_subscription( node, "/parameter_events", qos, std::forward(callback), options); } RCLCPP_PUBLIC bool service_is_ready() const; template bool wait_for_service( std::chrono::duration timeout = std::chrono::duration(-1)) { return wait_for_service_nanoseconds( std::chrono::duration_cast(timeout) ); } protected: RCLCPP_PUBLIC bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout); private: rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_; rclcpp::Client::SharedPtr get_parameters_client_; rclcpp::Client::SharedPtr get_parameter_types_client_; rclcpp::Client::SharedPtr set_parameters_client_; rclcpp::Client::SharedPtr set_parameters_atomically_client_; rclcpp::Client::SharedPtr list_parameters_client_; rclcpp::Client::SharedPtr describe_parameters_client_; std::string remote_node_name_; }; class SyncParametersClient { public: RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient) template explicit SyncParametersClient( std::shared_ptr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) : SyncParametersClient( std::make_shared(), node, remote_node_name, qos_profile) {} template SyncParametersClient( rclcpp::Executor::SharedPtr executor, std::shared_ptr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) : SyncParametersClient( executor, node->get_node_base_interface(), node->get_node_topics_interface(), node->get_node_graph_interface(), node->get_node_services_interface(), remote_node_name, qos_profile) {} template explicit SyncParametersClient( NodeT * node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) : SyncParametersClient( std::make_shared(), node, remote_node_name, qos_profile) {} template SyncParametersClient( rclcpp::Executor::SharedPtr executor, NodeT * node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) : SyncParametersClient( executor, node->get_node_base_interface(), node->get_node_topics_interface(), node->get_node_graph_interface(), node->get_node_services_interface(), remote_node_name, qos_profile) {} RCLCPP_PUBLIC SyncParametersClient( rclcpp::Executor::SharedPtr executor, const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) : executor_(executor), node_base_interface_(node_base_interface) { async_parameters_client_ = std::make_shared( node_base_interface, node_topics_interface, node_graph_interface, node_services_interface, remote_node_name, qos_profile); } template std::vector get_parameters( const std::vector & parameter_names, std::chrono::duration timeout = std::chrono::duration(-1)) { return get_parameters( parameter_names, std::chrono::duration_cast(timeout) ); } RCLCPP_PUBLIC bool has_parameter(const std::string & parameter_name); template T get_parameter_impl( const std::string & parameter_name, std::function parameter_not_found_handler) { std::vector names; names.push_back(parameter_name); auto vars = get_parameters(names); if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) { return parameter_not_found_handler(); } else { return static_cast(vars[0].get_value()); } } template T get_parameter(const std::string & parameter_name, const T & default_value) { return get_parameter_impl( parameter_name, std::function([&default_value]() -> T {return default_value;})); } template T get_parameter(const std::string & parameter_name) { return get_parameter_impl( parameter_name, std::function( [¶meter_name]() -> T { throw std::runtime_error("Parameter '" + parameter_name + "' is not set"); }) ); } template std::vector describe_parameters( const std::vector & parameter_names, std::chrono::duration timeout = std::chrono::duration(-1)) { return describe_parameters( parameter_names, std::chrono::duration_cast(timeout) ); } template std::vector get_parameter_types( const std::vector & parameter_names, std::chrono::duration timeout = std::chrono::duration(-1)) { return get_parameter_types( parameter_names, std::chrono::duration_cast(timeout) ); } template std::vector set_parameters( const std::vector & parameters, std::chrono::duration timeout = std::chrono::duration(-1)) { return set_parameters( parameters, std::chrono::duration_cast(timeout) ); } template rcl_interfaces::msg::SetParametersResult set_parameters_atomically( const std::vector & parameters, std::chrono::duration timeout = std::chrono::duration(-1)) { return set_parameters_atomically( parameters, std::chrono::duration_cast(timeout) ); } template std::vector delete_parameters( const std::vector & parameters_names, std::chrono::duration timeout = std::chrono::duration(-1)) { return delete_parameters( parameters_names, std::chrono::duration_cast(timeout) ); } template std::vector load_parameters( const std::string & yaml_filename, std::chrono::duration timeout = std::chrono::duration(-1)) { return load_parameters( yaml_filename, std::chrono::duration_cast(timeout) ); } template rcl_interfaces::msg::ListParametersResult list_parameters( const std::vector & parameter_prefixes, uint64_t depth, std::chrono::duration timeout = std::chrono::duration(-1)) { return list_parameters( parameter_prefixes, depth, std::chrono::duration_cast(timeout) ); } template typename rclcpp::Subscription::SharedPtr on_parameter_event(CallbackT && callback) { return async_parameters_client_->on_parameter_event( std::forward(callback)); } template< typename CallbackT, typename NodeT> static typename rclcpp::Subscription::SharedPtr on_parameter_event( NodeT && node, CallbackT && callback) { return AsyncParametersClient::on_parameter_event( node, std::forward(callback)); } RCLCPP_PUBLIC bool service_is_ready() const { return async_parameters_client_->service_is_ready(); } template bool wait_for_service( std::chrono::duration timeout = std::chrono::duration(-1)) { return async_parameters_client_->wait_for_service(timeout); } protected: RCLCPP_PUBLIC std::vector get_parameters( const std::vector & parameter_names, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC std::vector describe_parameters( const std::vector & parameter_names, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC std::vector get_parameter_types( const std::vector & parameter_names, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC std::vector set_parameters( const std::vector & parameters, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC std::vector delete_parameters( const std::vector & parameters_names, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC std::vector load_parameters( const std::string & yaml_filename, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically( const std::vector & parameters, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC rcl_interfaces::msg::ListParametersResult list_parameters( const std::vector & parameter_prefixes, uint64_t depth, std::chrono::nanoseconds timeout); private: rclcpp::Executor::SharedPtr executor_; const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_; AsyncParametersClient::SharedPtr async_parameters_client_; }; } // namespace rclcpp #endif // RCLCPP__PARAMETER_CLIENT_HPP_