ROS 2 rclcpp + rcl - rolling
rolling-a919a6e5
ROS 2 C++ Client Library with ROS Client Library
|
Public Member Functions | |
RCLCPP_PUBLIC | 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 rclcpp::QoS &qos_profile=rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr) |
Create an async parameters client. More... | |
template<typename NodeT > | |
AsyncParametersClient (const std::shared_ptr< NodeT > node, const std::string &remote_node_name="", const rclcpp::QoS &qos_profile=rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr) | |
template<typename NodeT > | |
AsyncParametersClient (NodeT *node, const std::string &remote_node_name="", const rclcpp::QoS &qos_profile=rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr) | |
RCLCPP_PUBLIC 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) |
RCLCPP_PUBLIC 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) |
RCLCPP_PUBLIC 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) |
RCLCPP_PUBLIC std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > | set_parameters (const std::vector< rclcpp::Parameter > ¶meters, std::function< void(std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult >>) > callback=nullptr) |
RCLCPP_PUBLIC std::shared_future< rcl_interfaces::msg::SetParametersResult > | set_parameters_atomically (const std::vector< rclcpp::Parameter > ¶meters, std::function< void(std::shared_future< rcl_interfaces::msg::SetParametersResult >) > callback=nullptr) |
RCLCPP_PUBLIC std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > | delete_parameters (const std::vector< std::string > ¶meters_names) |
Delete several parameters at once. More... | |
RCLCPP_PUBLIC std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > | load_parameters (const std::string &yaml_filename) |
Load parameters from yaml file. More... | |
RCLCPP_PUBLIC std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > | load_parameters (const rclcpp::ParameterMap ¶meter_map) |
Load parameters from parameter map. More... | |
RCLCPP_PUBLIC 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::ParameterEventsQoS(), const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >())) |
RCLCPP_PUBLIC 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::ParameterEventsQoS(), const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >())) |
Protected Member Functions | |
RCLCPP_PUBLIC bool | wait_for_service_nanoseconds (std::chrono::nanoseconds timeout) |
Definition at line 50 of file parameter_client.hpp.
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 rclcpp::QoS & | qos_profile = rclcpp::ParametersQoS() , |
||
rclcpp::CallbackGroup::SharedPtr | group = nullptr |
||
) |
Create an async parameters client.
[in] | node_base_interface | The node base interface of the corresponding node. |
[in] | node_topics_interface | Node topic base interface. |
[in] | node_graph_interface | The node graph interface of the corresponding node. |
[in] | node_services_interface | Node service interface. |
[in] | remote_node_name | (optional) name of the remote node |
[in] | qos_profile | (optional) The qos profile to use to subscribe |
[in] | group | (optional) The async parameter client will be added to this callback group. |
Definition at line 32 of file parameter_client.cpp.
References rclcpp::QoS::get_rmw_qos_profile(), rcl_client_options_s::qos, and rcl_client_get_default_options().
|
inlineexplicit |
[in] | node | The async parameters client will be added to this node. |
[in] | remote_node_name | (optional) name of the remote node |
[in] | qos_profile | (optional) The qos profile to use to subscribe |
[in] | group | (optional) The async parameter client will be added to this callback group. |
Definition at line 82 of file parameter_client.hpp.
|
inlineexplicit |
[in] | node | The async parameters client will be added to this node. |
[in] | remote_node_name | (optional) name of the remote node |
[in] | qos_profile | (optional) The qos profile to use to subscribe |
[in] | group | (optional) The async parameter client will be added to this callback group. |
Definition at line 104 of file parameter_client.hpp.
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > AsyncParametersClient::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_names | vector of parameters names |
Definition at line 277 of file parameter_client.cpp.
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > AsyncParametersClient::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.
If two duplicate keys exist in node names belongs to one FQN, there is no guarantee which one could be set.
parameter_map | named parameters to be loaded |
InvalidParametersException | if there is no parameter to set |
Definition at line 306 of file parameter_client.cpp.
References rclcpp::parameters_from_map().
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > AsyncParametersClient::load_parameters | ( | const std::string & | yaml_filename | ) |
Load parameters from yaml file.
This function behaves like command-line tool ros2 param load
would.
yaml_filename | the full name of the yaml file |
Definition at line 290 of file parameter_client.cpp.
References rclcpp::parameter_map_from_yaml_file().
|
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.
Definition at line 235 of file parameter_client.hpp.
bool AsyncParametersClient::service_is_ready | ( | ) | const |
Return if the parameter services are ready.
This method checks the following services:
true
if the service is ready, false
otherwise Definition at line 353 of file parameter_client.cpp.
References rclcpp::ClientBase::service_is_ready().
|
inline |
Wait for the services to be ready.
timeout | maximum time to wait |
true
if the services are ready and the timeout is not over, false
otherwise Definition at line 273 of file parameter_client.hpp.