Template Function rclcpp_action::create_server

Function Documentation

template<typename ActionT, typename NodeT>
Server<ActionT>::SharedPtr rclcpp_action::create_server(NodeT node, const std::string &name, typename Server<ActionT>::GoalCallback handle_goal, typename Server<ActionT>::CancelCallback handle_cancel, typename Server<ActionT>::AcceptedCallback handle_accepted, const rcl_action_server_options_t &options = rcl_action_server_get_default_options(), rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create an action server.

All provided callback functions must be non-blocking. This function is equivalent to

auto deleter = [weak_node, weak_group, group_is_null](

Server<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<Server<ActionT>> fake_shared_ptr(ptr, [](Server<ActionT> *) {});

See also

create_server()` however is using the individual node interfaces to create the server.

See also

Server::Server() for more information.

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<Server<ActionT>> action_server(new Server<ActionT>(

node_base_interface,

node_clock_interface,

node_logging_interface,

name,

options,

handle_goal,

handle_cancel,

handle_accepted), deleter);

node_waitables_interface->add_waitable(action_server, group); return action_server; }

Create an action server. /** All provided callback functions must be non-blocking.

See also

Server::Server() for more information.

Parameters:
  • node_base_interface[in] The node base interface of the corresponding node.

  • node_clock_interface[in] The node clock 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.

  • handle_goal[in] A callback that decides if a goal should be accepted or rejected.

  • handle_cancel[in] A callback that decides if a goal should be attempted to be canceled. The return from this callback only indicates if the server will try to cancel a goal. It does not indicate if the goal was actually canceled.

  • handle_accepted[in] A callback that is called to give the user a handle to the goal.

  • options[in] Options to pass to the underlying rcl_action_server_t.

  • group[in] The action server will be added to this callback group. If nullptr, then the action server is added to the default callback group. */ template<typename ActionT> typename Server<ActionT>::SharedPtr create_server( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string & name, typename Server<ActionT>::GoalCallback handle_goal, typename Server<ActionT>::CancelCallback handle_cancel, typename Server<ActionT>::AcceptedCallback handle_accepted, const rcl_action_server_options_t & options = rcl_action_server_get_default_options(), rclcpp::CallbackGroup::SharedPtr group = nullptr) { 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 server will be added to this node.

  • name[in] The action name.

  • handle_goal[in] A callback that decides if a goal should be accepted or rejected.

  • handle_cancel[in] A callback that decides if a goal should be attempted to be canceled. The return from this callback only indicates if the server will try to cancel a goal. It does not indicate if the goal was actually canceled.

  • handle_accepted[in] A callback that is called to give the user a handle to the goal.

  • options[in] Options to pass to the underlying rcl_action_server_t.

  • group[in] The action server will be added to this callback group. If nullptr, then the action server is added to the default callback group.