Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

improve SimpleActionServer #2459

Merged
merged 3 commits into from
Jul 26, 2021
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nav2_recoveries/include/nav2_recoveries/recovery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ template<typename ActionT>
class Recovery : public nav2_core::Recovery
{
public:
using ActionServer = nav2_util::SimpleActionServer<ActionT, rclcpp_lifecycle::LifecycleNode>;
using ActionServer = nav2_util::SimpleActionServer<ActionT>;

/**
* @brief A Recovery constructor
Expand Down
44 changes: 37 additions & 7 deletions nav2_util/include/nav2_util/simple_action_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "nav2_util/node_thread.hpp"

namespace nav2_util
{
Expand All @@ -32,7 +33,7 @@ namespace nav2_util
* @class nav2_util::SimpleActionServer
* @brief An action server wrapper to make applications simpler using Actions
*/
template<typename ActionT, typename nodeT = rclcpp::Node>
template<typename ActionT>
class SimpleActionServer
{
public:
Expand All @@ -54,19 +55,22 @@ class SimpleActionServer
* @param action_name Name of the action to call
* @param execute_callback Execution callback function of Action
* @param server_timeout Timeout to to react to stop or preemption requests
* @param spin_thread Whether to spin with a dedicated thread internally
*/
template<typename NodeT>
explicit SimpleActionServer(
typename nodeT::SharedPtr node,
NodeT node,
const std::string & action_name,
ExecuteCallback execute_callback,
CompletionCallback completion_callback = nullptr,
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500))
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
bool spin_thread = false)
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
: SimpleActionServer(
node->get_node_base_interface(),
node->get_node_clock_interface(),
node->get_node_logging_interface(),
node->get_node_waitables_interface(),
action_name, execute_callback, completion_callback, server_timeout)
action_name, execute_callback, completion_callback, server_timeout, spin_thread)
{}

/**
Expand All @@ -75,6 +79,7 @@ class SimpleActionServer
* @param action_name Name of the action to call
* @param execute_callback Execution callback function of Action
* @param server_timeout Timeout to to react to stop or preemption requests
* @param spin_thread Whether to spin with a dedicated thread internally
*/
explicit SimpleActionServer(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
Expand All @@ -84,17 +89,23 @@ class SimpleActionServer
const std::string & action_name,
ExecuteCallback execute_callback,
CompletionCallback completion_callback = nullptr,
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500))
std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
bool spin_thread = false)
: node_base_interface_(node_base_interface),
node_clock_interface_(node_clock_interface),
node_logging_interface_(node_logging_interface),
node_waitables_interface_(node_waitables_interface),
action_name_(action_name),
execute_callback_(execute_callback),
completion_callback_(completion_callback),
server_timeout_(server_timeout)
server_timeout_(server_timeout),
spin_thread_(spin_thread)
{
using namespace std::placeholders; // NOLINT
if (spin_thread_) {
callback_group_ = node_base_interface->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive, false);
}
action_server_ = rclcpp_action::create_server<ActionT>(
node_base_interface_,
node_clock_interface_,
Expand All @@ -103,9 +114,25 @@ class SimpleActionServer
action_name_,
std::bind(&SimpleActionServer::handle_goal, this, _1, _2),
std::bind(&SimpleActionServer::handle_cancel, this, _1),
std::bind(&SimpleActionServer::handle_accepted, this, _1));
std::bind(&SimpleActionServer::handle_accepted, this, _1),
rcl_action_server_get_default_options(),
callback_group_);
if (spin_thread_) {
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
executor->add_callback_group(callback_group_, node_base_interface_);
executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor);
}
}

/**
* @brief A destructor
*/
~SimpleActionServer()
{
if (spin_thread_) {
executor_thread_.reset();
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
}
}
/**
* @brief handle the goal requested: accept or reject. This implementation always accepts.
* @param uuid Goal ID
Expand Down Expand Up @@ -485,6 +512,9 @@ class SimpleActionServer
std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> pending_handle_;

typename rclcpp_action::Server<ActionT>::SharedPtr action_server_;
bool spin_thread_;
rclcpp::CallbackGroup::SharedPtr callback_group_{nullptr};
std::unique_ptr<nav2_util::NodeThread> executor_thread_;

/**
* @brief Generate an empty result object for an action type
Expand Down