Class SyncParametersClient
Defined in File parameter_client.hpp
Class Documentation
-
class SyncParametersClient
Public Functions
-
template<typename NodeT>
inline SyncParametersClient(NodeT *node, const std::string &remote_node_name, const rmw_qos_profile_t &qos_profile)
-
template<typename NodeT>
inline explicit SyncParametersClient(NodeT *node, const std::string &remote_node_name = "", const rclcpp::QoS &qos_profile = rclcpp::ParametersQoS())
-
template<typename RepT = int64_t, typename RatioT = std::milli>
inline std::vector<rclcpp::Parameter> get_parameters(const std::vector<std::string> ¶meter_names, std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
-
bool has_parameter(const std::string ¶meter_name)
-
template<typename T>
inline T get_parameter_impl(const std::string ¶meter_name, std::function<T()> parameter_not_found_handler)
-
template<typename T>
inline T get_parameter(const std::string ¶meter_name, const T &default_value)
-
template<typename RepT = int64_t, typename RatioT = std::milli>
inline std::vector<rcl_interfaces::msg::ParameterDescriptor> describe_parameters(const std::vector<std::string> ¶meter_names, std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
-
template<typename RepT = int64_t, typename RatioT = std::milli>
inline std::vector<rclcpp::ParameterType> get_parameter_types(const std::vector<std::string> ¶meter_names, std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
-
template<typename RepT = int64_t, typename RatioT = std::milli>
inline std::vector<rcl_interfaces::msg::SetParametersResult> set_parameters(const std::vector<rclcpp::Parameter> ¶meters, std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
-
template<typename RepT = int64_t, typename RatioT = std::milli>
inline rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector<rclcpp::Parameter> ¶meters, std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
-
template<typename RepT = int64_t, typename RatioT = std::milli>
inline std::vector<rcl_interfaces::msg::SetParametersResult> delete_parameters(const std::vector<std::string> ¶meters_names, std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1)) Delete several parameters at once.
This function behaves like command-line tool
ros2 param delete
would.- Parameters:
parameters_names – vector of parameters names
timeout – for the spin used to make it synchronous
- Returns:
the future of the set_parameter service used to delete the parameters
-
template<typename RepT = int64_t, typename RatioT = std::milli>
inline 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.
This function behaves like command-line tool
ros2 param load
would.- Parameters:
yaml_filename – the full name of the yaml file
timeout – for the spin used to make it synchronous
- Returns:
the future of the set_parameter service used to load the parameters
-
template<typename RepT = int64_t, typename RatioT = std::milli>
inline rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector<std::string> ¶meter_prefixes, uint64_t depth, std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
-
inline bool service_is_ready() const
Public Static Functions
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
-
std::vector<rclcpp::Parameter> get_parameters(const std::vector<std::string> ¶meter_names, std::chrono::nanoseconds timeout)
-
std::vector<rcl_interfaces::msg::ParameterDescriptor> describe_parameters(const std::vector<std::string> ¶meter_names, std::chrono::nanoseconds timeout)
-
std::vector<rclcpp::ParameterType> get_parameter_types(const std::vector<std::string> ¶meter_names, std::chrono::nanoseconds timeout)
-
std::vector<rcl_interfaces::msg::SetParametersResult> set_parameters(const std::vector<rclcpp::Parameter> ¶meters, std::chrono::nanoseconds timeout)
-
std::vector<rcl_interfaces::msg::SetParametersResult> delete_parameters(const std::vector<std::string> ¶meters_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> ¶meters, std::chrono::nanoseconds timeout)
-
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector<std::string> ¶meter_prefixes, uint64_t depth, std::chrono::nanoseconds timeout)
-
template<typename NodeT>