rclcpp  master
C++ ROS Client Library API
Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
rclcpp::AsyncParametersClient Class Reference

#include <parameter_client.hpp>

Public Member 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. More...
 
 AsyncParametersClient (const rclcpp::Node::SharedPtr node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group=nullptr)
 Constructor. More...
 
 AsyncParametersClient (rclcpp::Node *node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group=nullptr)
 Constructor. More...
 
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< 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< 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>>
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. More...
 
template<typename RepT = int64_t, typename RatioT = std::milli>
bool wait_for_service (std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 Wait for the services to be ready. More...
 

Static Public Member Functions

template<typename CallbackT , typename NodeT , typename AllocatorT = std::allocator<void>>
static 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 >()))
 

Protected Member Functions

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

Constructor & Destructor Documentation

◆ AsyncParametersClient() [1/3]

rclcpp::AsyncParametersClient::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
[in]node_base_interfaceThe node base interface of the corresponding node.
[in]node_topics_interfaceNode topic base interface.
[in]node_graph_interfaceThe node graph interface of the corresponding node.
[in]node_services_interfaceNode service interface.
[in]remote_node_name(optional) name of the remote node
[in]qos_profile(optional) The rmw qos profile to use to subscribe
[in]group(optional) The async parameter client will be added to this callback group.

◆ AsyncParametersClient() [2/3]

rclcpp::AsyncParametersClient::AsyncParametersClient ( const rclcpp::Node::SharedPtr  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
[in]nodeThe async paramters client will be added to this node.
[in]remote_node_name(optional) name of the remote node
[in]qos_profile(optional) The rmw qos profile to use to subscribe
[in]group(optional) The async parameter client will be added to this callback group.

◆ AsyncParametersClient() [3/3]

rclcpp::AsyncParametersClient::AsyncParametersClient ( rclcpp::Node 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
[in]nodeThe async paramters client will be added to this node.
[in]remote_node_name(optional) name of the remote node
[in]qos_profile(optional) The rmw qos profile to use to subscribe
[in]group(optional) The async parameter client will be added to this callback group.

Member Function Documentation

◆ get_parameters()

std::shared_future<std::vector<rclcpp::Parameter> > rclcpp::AsyncParametersClient::get_parameters ( const std::vector< std::string > &  names,
std::function< void(std::shared_future< std::vector< rclcpp::Parameter >>) >  callback = nullptr 
)

◆ get_parameter_types()

std::shared_future<std::vector<rclcpp::ParameterType> > rclcpp::AsyncParametersClient::get_parameter_types ( const std::vector< std::string > &  names,
std::function< void(std::shared_future< std::vector< rclcpp::ParameterType >>) >  callback = nullptr 
)

◆ set_parameters()

std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult> > rclcpp::AsyncParametersClient::set_parameters ( const std::vector< rclcpp::Parameter > &  parameters,
std::function< void(std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult >>) >  callback = nullptr 
)

◆ set_parameters_atomically()

std::shared_future<rcl_interfaces::msg::SetParametersResult> rclcpp::AsyncParametersClient::set_parameters_atomically ( const std::vector< rclcpp::Parameter > &  parameters,
std::function< void(std::shared_future< rcl_interfaces::msg::SetParametersResult >) >  callback = nullptr 
)

◆ list_parameters()

std::shared_future<rcl_interfaces::msg::ListParametersResult> rclcpp::AsyncParametersClient::list_parameters ( const std::vector< std::string > &  prefixes,
uint64_t  depth,
std::function< void(std::shared_future< rcl_interfaces::msg::ListParametersResult >) >  callback = nullptr 
)

◆ on_parameter_event() [1/2]

template<typename CallbackT , typename AllocatorT = std::allocator<void>>
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr rclcpp::AsyncParametersClient::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>()  ) 
)
inline

◆ on_parameter_event() [2/2]

template<typename CallbackT , typename NodeT , typename AllocatorT = std::allocator<void>>
static rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr rclcpp::AsyncParametersClient::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>()  ) 
)
inlinestatic

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.

◆ service_is_ready()

bool rclcpp::AsyncParametersClient::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

◆ wait_for_service()

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

Wait for the services to be ready.

Parameters
timeoutmaximum time to wait
Returns
true if the services are ready and the timeout is not over, false otherwise

◆ wait_for_service_nanoseconds()

bool rclcpp::AsyncParametersClient::wait_for_service_nanoseconds ( std::chrono::nanoseconds  timeout)
protected

The documentation for this class was generated from the following file: