Template Function rclcpp_action::create_client
Defined in File create_client.hpp
Function Documentation
Create an action client.
This function is equivalent to
auto deleter = [weak_node, weak_group, group_is_null](
Client<ActionT> * ptr) { if (nullptr == ptr) { return; } auto shared_node = weak_node.lock(); if (shared_node) { API expects a shared pointer, give it one with a deleter that does nothing. std::shared_ptr<Client<ActionT>> fake_shared_ptr(ptr, [](Client<ActionT> *) {});See also
create_client()` however is using the individual node interfaces to create the client.
if (group_is_null) { Was added to default group shared_node->remove_waitable(fake_shared_ptr, nullptr); } else { Was added to a specific group auto shared_group = weak_group.lock(); if (shared_group) { shared_node->remove_waitable(fake_shared_ptr, shared_group); } } } delete ptr; };
std::shared_ptr<Client<ActionT>> action_client(
new Client<ActionT>(
node_base_interface,
node_graph_interface,
node_logging_interface,
name,
options),
deleter);
node_waitables_interface->add_waitable(action_client, group); return action_client; }
Create an action client. /**
- Parameters:
node_base_interface – [in] The node base interface of the corresponding node.
node_graph_interface – [in] The node graph interface of the corresponding node.
node_logging_interface – [in] The node logging interface of the corresponding node.
node_waitables_interface – [in] The node waitables interface of the corresponding node.
name – [in] The action name.
group – [in] The action client will be added to this callback group. If
nullptr, then the action client is added to the default callback group.options – [in] Options to pass to the underlying
rcl_action_client_t. */ template<typename ActionT> typename Client<ActionT>::SharedPtr create_client( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string & name, rclcpp::CallbackGroup::SharedPtr group = nullptr, const rcl_action_client_options_t & options = rcl_action_client_get_default_options()) { std::weak_ptr<rclcpp::node_interfaces::NodeWaitablesInterface> weak_node = node_waitables_interface; std::weak_ptr<rclcpp::CallbackGroup> weak_group = group; bool group_is_null = (nullptr == group.get());node – [in] The action client will be added to this node.
name – [in] The action name.
group – [in] The action client will be added to this callback group. If
nullptr, then the action client is added to the default callback group.options – [in] Options to pass to the underlying
rcl_action_client_t.