Class AsyncParametersClient

Class Documentation

class AsyncParametersClient

Public Functions

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)

Create an async parameters client.

Parameters:
  • node_base_interface[in] The node base interface of the corresponding node.

  • node_topics_interface[in] Node topic base interface.

  • node_graph_interface[in] The node graph interface of the corresponding node.

  • node_services_interface[in] Node service interface.

  • remote_node_name[in] (optional) name of the remote node

  • qos_profile[in] (optional) The rmw qos profile to use to subscribe

  • group[in] (optional) The async parameter client will be added to this callback group.

template<typename NodeT>
inline explicit AsyncParametersClient(const std::shared_ptr<NodeT> node, const std::string &remote_node_name = "", const rmw_qos_profile_t &qos_profile = rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Constructor.

Parameters:
  • node[in] The async paramters client will be added to this node.

  • remote_node_name[in] (optional) name of the remote node

  • qos_profile[in] (optional) The rmw qos profile to use to subscribe

  • group[in] (optional) The async parameter client will be added to this callback group.

template<typename NodeT>
inline 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)

Constructor.

Parameters:
  • node[in] The async paramters client will be added to this node.

  • remote_node_name[in] (optional) name of the remote node

  • qos_profile[in] (optional) The rmw qos profile to use to subscribe

  • group[in] (optional) The async parameter client will be added to this callback group.

std::shared_future<std::vector<rclcpp::Parameter>> get_parameters(const std::vector<std::string> &names, std::function<void(std::shared_future<std::vector<rclcpp::Parameter>>)> callback = nullptr)
std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>> describe_parameters(const std::vector<std::string> &names, std::function<void(std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>)> callback = nullptr)
std::shared_future<std::vector<rclcpp::ParameterType>> get_parameter_types(const std::vector<std::string> &names, std::function<void(std::shared_future<std::vector<rclcpp::ParameterType>>)> callback = nullptr)
std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>> set_parameters(const std::vector<rclcpp::Parameter> &parameters, std::function<void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)> callback = nullptr)
std::shared_future<rcl_interfaces::msg::SetParametersResult> set_parameters_atomically(const std::vector<rclcpp::Parameter> &parameters, std::function<void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)> callback = nullptr)
std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>> delete_parameters(const std::vector<std::string> &parameters_names)

Delete several parameters at once.

This function behaves like command-line tool ros2 param delete would.

Parameters:

parameters_names – vector of parameters names

Returns:

the future of the set_parameter service used to delete the parameters

std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>> load_parameters(const std::string &yaml_filename)

Load parameters from yaml file.

This function behaves like command-line tool ros2 param load would.

Parameters:

yaml_filename – the full name of the yaml file

Returns:

the future of the set_parameter service used to load the parameters

std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>> load_parameters(const rclcpp::ParameterMap &parameter_map)

Load parameters from parameter map.

This function filters the parameters to be set based on the node name.

Parameters:

parameter_map – named parameters to be loaded

Throws:

InvalidParametersException – if there is no parameter to set

Returns:

the future of the set_parameter service used to load the parameters

std::shared_future<rcl_interfaces::msg::ListParametersResult> list_parameters(const std::vector<std::string> &prefixes, uint64_t depth, std::function<void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)> callback = nullptr)
template<typename CallbackT, typename AllocatorT = std::allocator<void>>
inline rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr on_parameter_event(CallbackT &&callback, const rclcpp::QoS &qos = (rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))), const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &options = (rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()))
bool service_is_ready() const

Return if the parameter services are ready.

This method checks the following services:

  • get parameter

  • get parameter

  • set parameters

  • list parameters

  • describe parameters

Returns:

true if the service is ready, false otherwise

template<typename RepT = int64_t, typename RatioT = std::milli>
inline bool wait_for_service(std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))

Wait for the services to be ready.

Parameters:

timeout – maximum time to wait

Returns:

true if the services are ready and the timeout is not over, false otherwise

Public Static Functions

template<typename CallbackT, typename NodeT, typename AllocatorT = std::allocator<void>>
static inline rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::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<AllocatorT> &options = (rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()))

The NodeT type only needs to have a method called get_node_topics_interface() which returns a shared_ptr to a NodeTopicsInterface, or be a NodeTopicsInterface pointer itself.

Protected Functions

bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)