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

#include <parameter_client.hpp>

Public Member Functions

 SyncParametersClient (rclcpp::Node::SharedPtr node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
 
 SyncParametersClient (rclcpp::Executor::SharedPtr executor, rclcpp::Node::SharedPtr node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
 
 SyncParametersClient (rclcpp::Node *node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
 
 SyncParametersClient (rclcpp::Executor::SharedPtr executor, rclcpp::Node *node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
 
 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)
 
std::vector< rclcpp::Parameterget_parameters (const std::vector< std::string > &parameter_names)
 
bool has_parameter (const std::string &parameter_name)
 
template<typename T >
get_parameter_impl (const std::string &parameter_name, std::function< T()> parameter_not_found_handler)
 
template<typename T >
get_parameter (const std::string &parameter_name, const T &default_value)
 
template<typename T >
get_parameter (const std::string &parameter_name)
 
std::vector< rclcpp::ParameterTypeget_parameter_types (const std::vector< std::string > &parameter_names)
 
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters (const std::vector< rclcpp::Parameter > &parameters)
 
rcl_interfaces::msg::SetParametersResult set_parameters_atomically (const std::vector< rclcpp::Parameter > &parameters)
 
rcl_interfaces::msg::ListParametersResult list_parameters (const std::vector< std::string > &parameter_prefixes, uint64_t depth)
 
template<typename CallbackT >
rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event (CallbackT &&callback)
 
bool service_is_ready () const
 
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))
 

Static Public Member Functions

template<typename CallbackT , typename NodeT >
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event (NodeT &&node, CallbackT &&callback)
 

Constructor & Destructor Documentation

◆ SyncParametersClient() [1/5]

rclcpp::SyncParametersClient::SyncParametersClient ( rclcpp::Node::SharedPtr  node,
const std::string remote_node_name = "",
const rmw_qos_profile_t qos_profile = rmw_qos_profile_parameters 
)
explicit

◆ SyncParametersClient() [2/5]

rclcpp::SyncParametersClient::SyncParametersClient ( rclcpp::Executor::SharedPtr  executor,
rclcpp::Node::SharedPtr  node,
const std::string remote_node_name = "",
const rmw_qos_profile_t qos_profile = rmw_qos_profile_parameters 
)

◆ SyncParametersClient() [3/5]

rclcpp::SyncParametersClient::SyncParametersClient ( rclcpp::Node node,
const std::string remote_node_name = "",
const rmw_qos_profile_t qos_profile = rmw_qos_profile_parameters 
)
explicit

◆ SyncParametersClient() [4/5]

rclcpp::SyncParametersClient::SyncParametersClient ( rclcpp::Executor::SharedPtr  executor,
rclcpp::Node node,
const std::string remote_node_name = "",
const rmw_qos_profile_t qos_profile = rmw_qos_profile_parameters 
)

◆ SyncParametersClient() [5/5]

rclcpp::SyncParametersClient::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 
)

Member Function Documentation

◆ get_parameters()

std::vector<rclcpp::Parameter> rclcpp::SyncParametersClient::get_parameters ( const std::vector< std::string > &  parameter_names)

◆ has_parameter()

bool rclcpp::SyncParametersClient::has_parameter ( const std::string parameter_name)

◆ get_parameter_impl()

template<typename T >
T rclcpp::SyncParametersClient::get_parameter_impl ( const std::string parameter_name,
std::function< T()>  parameter_not_found_handler 
)
inline

◆ get_parameter() [1/2]

template<typename T >
T rclcpp::SyncParametersClient::get_parameter ( const std::string parameter_name,
const T &  default_value 
)
inline

◆ get_parameter() [2/2]

template<typename T >
T rclcpp::SyncParametersClient::get_parameter ( const std::string parameter_name)
inline

◆ get_parameter_types()

std::vector<rclcpp::ParameterType> rclcpp::SyncParametersClient::get_parameter_types ( const std::vector< std::string > &  parameter_names)

◆ set_parameters()

std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::SyncParametersClient::set_parameters ( const std::vector< rclcpp::Parameter > &  parameters)

◆ set_parameters_atomically()

rcl_interfaces::msg::SetParametersResult rclcpp::SyncParametersClient::set_parameters_atomically ( const std::vector< rclcpp::Parameter > &  parameters)

◆ list_parameters()

rcl_interfaces::msg::ListParametersResult rclcpp::SyncParametersClient::list_parameters ( const std::vector< std::string > &  parameter_prefixes,
uint64_t  depth 
)

◆ on_parameter_event() [1/2]

template<typename CallbackT >
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr rclcpp::SyncParametersClient::on_parameter_event ( CallbackT &&  callback)
inline

◆ on_parameter_event() [2/2]

template<typename CallbackT , typename NodeT >
static rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr rclcpp::SyncParametersClient::on_parameter_event ( NodeT &&  node,
CallbackT &&  callback 
)
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::SyncParametersClient::service_is_ready ( ) const
inline

◆ wait_for_service()

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

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