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

#include <parameter_client.hpp>

Public Member Functions

template<typename NodeT >
 SyncParametersClient (std::shared_ptr< NodeT > node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
 
template<typename NodeT >
 SyncParametersClient (rclcpp::Executor::SharedPtr executor, std::shared_ptr< NodeT > node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
 
template<typename NodeT >
 SyncParametersClient (NodeT *node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
 
template<typename NodeT >
 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 (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)
 
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector< rclcpp::Parameterget_parameters (const std::vector< std::string > &parameter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 
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)
 
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters (const std::vector< std::string > &parameter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector< rclcpp::ParameterTypeget_parameter_types (const std::vector< std::string > &parameter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters (const std::vector< rclcpp::Parameter > &parameters, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 
template<typename RepT = int64_t, typename RatioT = std::milli>
rcl_interfaces::msg::SetParametersResult set_parameters_atomically (const std::vector< rclcpp::Parameter > &parameters, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector< rcl_interfaces::msg::SetParametersResult > delete_parameters (const std::vector< std::string > &parameters_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 Delete several parameters at once. More...
 
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector< rcl_interfaces::msg::SetParametersResult > load_parameters (const std::string &yaml_filename, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 Load parameters from yaml file. More...
 
template<typename RepT = int64_t, typename RatioT = std::milli>
rcl_interfaces::msg::ListParametersResult list_parameters (const std::vector< std::string > &parameter_prefixes, uint64_t depth, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
 
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)
 

Protected Member Functions

std::vector< rclcpp::Parameterget_parameters (const std::vector< std::string > &parameter_names, std::chrono::nanoseconds timeout)
 
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters (const std::vector< std::string > &parameter_names, std::chrono::nanoseconds timeout)
 
std::vector< rclcpp::ParameterTypeget_parameter_types (const std::vector< std::string > &parameter_names, std::chrono::nanoseconds timeout)
 
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters (const std::vector< rclcpp::Parameter > &parameters, std::chrono::nanoseconds timeout)
 
std::vector< rcl_interfaces::msg::SetParametersResult > delete_parameters (const std::vector< std::string > &parameters_names, std::chrono::nanoseconds timeout)
 
std::vector< rcl_interfaces::msg::SetParametersResult > load_parameters (const std::string &yaml_filename, std::chrono::nanoseconds timeout)
 
rcl_interfaces::msg::SetParametersResult set_parameters_atomically (const std::vector< rclcpp::Parameter > &parameters, std::chrono::nanoseconds timeout)
 
rcl_interfaces::msg::ListParametersResult list_parameters (const std::vector< std::string > &parameter_prefixes, uint64_t depth, std::chrono::nanoseconds timeout)
 

Constructor & Destructor Documentation

◆ SyncParametersClient() [1/5]

template<typename NodeT >
rclcpp::SyncParametersClient::SyncParametersClient ( std::shared_ptr< NodeT >  node,
const std::string remote_node_name = "",
const rmw_qos_profile_t qos_profile = rmw_qos_profile_parameters 
)
inlineexplicit

◆ SyncParametersClient() [2/5]

template<typename NodeT >
rclcpp::SyncParametersClient::SyncParametersClient ( rclcpp::Executor::SharedPtr  executor,
std::shared_ptr< NodeT >  node,
const std::string remote_node_name = "",
const rmw_qos_profile_t qos_profile = rmw_qos_profile_parameters 
)
inline

◆ SyncParametersClient() [3/5]

template<typename NodeT >
rclcpp::SyncParametersClient::SyncParametersClient ( NodeT *  node,
const std::string remote_node_name = "",
const rmw_qos_profile_t qos_profile = rmw_qos_profile_parameters 
)
inline

◆ SyncParametersClient() [4/5]

template<typename NodeT >
rclcpp::SyncParametersClient::SyncParametersClient ( rclcpp::Executor::SharedPtr  executor,
NodeT *  node,
const std::string remote_node_name = "",
const rmw_qos_profile_t qos_profile = rmw_qos_profile_parameters 
)
inline

◆ 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 
)
inline

Member Function Documentation

◆ get_parameters() [1/2]

template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rclcpp::Parameter> rclcpp::SyncParametersClient::get_parameters ( const std::vector< std::string > &  parameter_names,
std::chrono::duration< RepT, RatioT >  timeout = std::chrono::duration<RepT, RatioT>(-1) 
)
inline

◆ 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

◆ describe_parameters() [1/2]

template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rcl_interfaces::msg::ParameterDescriptor> rclcpp::SyncParametersClient::describe_parameters ( const std::vector< std::string > &  parameter_names,
std::chrono::duration< RepT, RatioT >  timeout = std::chrono::duration<RepT, RatioT>(-1) 
)
inline

◆ get_parameter_types() [1/2]

template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rclcpp::ParameterType> rclcpp::SyncParametersClient::get_parameter_types ( const std::vector< std::string > &  parameter_names,
std::chrono::duration< RepT, RatioT >  timeout = std::chrono::duration<RepT, RatioT>(-1) 
)
inline

◆ set_parameters() [1/2]

template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::SyncParametersClient::set_parameters ( const std::vector< rclcpp::Parameter > &  parameters,
std::chrono::duration< RepT, RatioT >  timeout = std::chrono::duration<RepT, RatioT>(-1) 
)
inline

◆ set_parameters_atomically() [1/2]

template<typename RepT = int64_t, typename RatioT = std::milli>
rcl_interfaces::msg::SetParametersResult rclcpp::SyncParametersClient::set_parameters_atomically ( const std::vector< rclcpp::Parameter > &  parameters,
std::chrono::duration< RepT, RatioT >  timeout = std::chrono::duration<RepT, RatioT>(-1) 
)
inline

◆ delete_parameters() [1/2]

template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::SyncParametersClient::delete_parameters ( const std::vector< std::string > &  parameters_names,
std::chrono::duration< RepT, RatioT >  timeout = std::chrono::duration<RepT, RatioT>(-1) 
)
inline

Delete several parameters at once.

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

Parameters
parameters_namesvector of parameters names
timeoutfor the spin used to make it synchronous
Returns
the future of the set_parameter service used to delete the parameters

◆ load_parameters() [1/2]

template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::SyncParametersClient::load_parameters ( const std::string yaml_filename,
std::chrono::duration< RepT, RatioT >  timeout = std::chrono::duration<RepT, RatioT>(-1) 
)
inline

Load parameters from yaml file.

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

Parameters
yaml_filenamethe full name of the yaml file
timeoutfor the spin used to make it synchronous
Returns
the future of the set_parameter service used to load the parameters

◆ list_parameters() [1/2]

template<typename RepT = int64_t, typename RatioT = std::milli>
rcl_interfaces::msg::ListParametersResult rclcpp::SyncParametersClient::list_parameters ( const std::vector< std::string > &  parameter_prefixes,
uint64_t  depth,
std::chrono::duration< RepT, RatioT >  timeout = std::chrono::duration<RepT, RatioT>(-1) 
)
inline

◆ 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

◆ get_parameters() [2/2]

std::vector<rclcpp::Parameter> rclcpp::SyncParametersClient::get_parameters ( const std::vector< std::string > &  parameter_names,
std::chrono::nanoseconds  timeout 
)
protected

◆ describe_parameters() [2/2]

std::vector<rcl_interfaces::msg::ParameterDescriptor> rclcpp::SyncParametersClient::describe_parameters ( const std::vector< std::string > &  parameter_names,
std::chrono::nanoseconds  timeout 
)
protected

◆ get_parameter_types() [2/2]

std::vector<rclcpp::ParameterType> rclcpp::SyncParametersClient::get_parameter_types ( const std::vector< std::string > &  parameter_names,
std::chrono::nanoseconds  timeout 
)
protected

◆ set_parameters() [2/2]

std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::SyncParametersClient::set_parameters ( const std::vector< rclcpp::Parameter > &  parameters,
std::chrono::nanoseconds  timeout 
)
protected

◆ delete_parameters() [2/2]

std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::SyncParametersClient::delete_parameters ( const std::vector< std::string > &  parameters_names,
std::chrono::nanoseconds  timeout 
)
protected

◆ load_parameters() [2/2]

std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::SyncParametersClient::load_parameters ( const std::string yaml_filename,
std::chrono::nanoseconds  timeout 
)
protected

◆ set_parameters_atomically() [2/2]

rcl_interfaces::msg::SetParametersResult rclcpp::SyncParametersClient::set_parameters_atomically ( const std::vector< rclcpp::Parameter > &  parameters,
std::chrono::nanoseconds  timeout 
)
protected

◆ list_parameters() [2/2]

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

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