rclcpp_action
master
C++ ROS Action Client Library
|
Go to the documentation of this file.
15 #ifndef RCLCPP_ACTION__SERVER_HPP_
16 #define RCLCPP_ACTION__SERVER_HPP_
18 #include <rcl_action/action_server.h>
19 #include <rosidl_runtime_c/action_type_support_struct.h>
20 #include <rosidl_typesupport_cpp/action_type_support.hpp>
30 #include <unordered_map>
137 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
138 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
139 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
141 const rosidl_action_type_support_t * type_support,
254 execute_check_expired_goals();
271 template<
typename ActionT>
312 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
313 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
314 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
326 rosidl_typesupport_cpp::get_action_type_support_handle<ActionT>(),
328 handle_goal_(handle_goal),
329 handle_cancel_(handle_cancel),
330 handle_accepted_(handle_accepted)
345 typename ActionT::Impl::SendGoalService::Request>(message);
349 auto ros_response = std::make_shared<typename ActionT::Impl::SendGoalService::Response>();
362 auto element = goal_handles_.find(uuid);
363 if (element != goal_handles_.end()) {
364 goal_handle = element->second.lock();
370 resp = handle_cancel_(goal_handle);
373 goal_handle->_cancel_goal();
377 "Failed to cancel goal in call_handle_cancel_callback: %s", ex.
what());
402 shared_this->publish_result(goal_uuid, result_message);
404 shared_this->publish_status();
406 shared_this->notify_goal_terminal_state();
409 shared_this->goal_handles_.erase(goal_uuid);
413 [weak_this](
const GoalUUID & goal_uuid)
421 shared_this->publish_status();
431 shared_this->publish_feedback(std::static_pointer_cast<void>(feedback_msg));
435 const typename ActionT::Impl::SendGoalService::Request>(goal_request_message);
439 rcl_goal_handle, uuid, goal, on_terminal_state, on_executing,
publish_feedback));
442 goal_handles_[uuid] = goal_handle;
444 handle_accepted_(goal_handle);
452 static_cast<typename ActionT::Impl::SendGoalService::Request *
>(message)->goal_id.uuid;
467 static_cast<typename ActionT::Impl::GetResultService::Request *
>(message)->goal_id.uuid;
481 auto result = std::make_shared<typename ActionT::Impl::GetResultService::Response>();
482 result->status = status;
483 return std::static_pointer_cast<void>(result);
501 #endif // RCLCPP_ACTION__SERVER_HPP_
RCLCPP_ACTION_PUBLIC void publish_feedback(std::shared_ptr< void > feedback_msg)
virtual RCLCPP_ACTION_PUBLIC std::shared_ptr< void > create_goal_request()=0
GoalResponse
A response returned by an action server callback when a goal is requested.
Definition: server.hpp:43
@ ACCEPT_AND_EXECUTE
The server accepts the goal, and is going to begin execution immediately.
RCLCPP_ACTION_PUBLIC void notify_goal_terminal_state()
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_timers() override
virtual RCLCPP_ACTION_PUBLIC CancelResponse call_handle_cancel_callback(const GoalUUID &uuid)=0
virtual ~Server()=default
RCLCPP_ACTION_PUBLIC void publish_status()
Logger get_logger(const std::string &name)
@ REJECT
The server will not try to cancel the goal.
std::shared_ptr< void > create_result_request() override
Definition: server.hpp:472
virtual RCLCPP_ACTION_PUBLIC std::pair< GoalResponse, std::shared_ptr< void > > call_handle_goal_callback(GoalUUID &, std::shared_ptr< void > request)=0
std::shared_ptr< void > create_goal_request() override
Definition: server.hpp:457
RCLCPP_ACTION_PUBLIC bool is_ready(rcl_wait_set_t *) override
Definition: client.hpp:46
GoalUUID get_goal_id_from_goal_request(void *message) override
Definition: server.hpp:449
std::shared_ptr< void > create_result_response(decltype(action_msgs::msg::GoalStatus::status) status) override
Definition: server.hpp:479
virtual RCLCPP_ACTION_PUBLIC std::shared_ptr< void > create_result_request()=0
virtual RCLCPP_ACTION_PUBLIC GoalUUID get_goal_id_from_goal_request(void *message)=0
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_guard_conditions() override
T shared_from_this(T... args)
Server(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const std::string &name, const rcl_action_server_options_t &options, GoalCallback handle_goal, CancelCallback handle_cancel, AcceptedCallback handle_accepted)
Construct an action server.
Definition: server.hpp:311
@ REJECT
The goal is rejected and will not be executed.
virtual RCLCPP_ACTION_PUBLIC ~ServerBase()
T static_pointer_cast(T... args)
std::function< CancelResponse(std::shared_ptr< ServerGoalHandle< ActionT > >)> CancelCallback
Signature of a callback that accepts or rejects requests to cancel a goal.
Definition: server.hpp:281
RCLCPP_ACTION_PUBLIC void execute(std::shared_ptr< void > &data) override
#define RCLCPP_DEBUG(logger,...)
RCLCPP_ACTION_PUBLIC std::shared_ptr< void > take_data() override
virtual RCLCPP_ACTION_PUBLIC void call_goal_accepted_callback(std::shared_ptr< rcl_action_goal_handle_t > rcl_goal_handle, GoalUUID uuid, std::shared_ptr< void > goal_request_message)=0
virtual RCLCPP_ACTION_PUBLIC std::shared_ptr< void > create_result_response(decltype(action_msgs::msg::GoalStatus::status) status)=0
Action Server.
Definition: server.hpp:272
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_clients() override
CancelResponse call_handle_cancel_callback(const GoalUUID &uuid) override
Definition: server.hpp:357
std::function< GoalResponse(const GoalUUID &, std::shared_ptr< const typename ActionT::Goal >)> GoalCallback
Signature of a callback that accepts or rejects goal requests.
Definition: server.hpp:279
@ ACCEPT
The server has agreed to try to cancel the goal.
@ ACCEPT_AND_DEFER
The server accepts the goal, and is going to execute it later.
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_subscriptions() override
CancelResponse
A response returned by an action server callback when a goal has been asked to be canceled.
Definition: server.hpp:54
#define RCLCPP_ACTION_PUBLIC
Definition: visibility_control.hpp:50
virtual RCLCPP_ACTION_PUBLIC GoalUUID get_goal_id_from_result_request(void *message)=0
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_services() override
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
void call_goal_accepted_callback(std::shared_ptr< rcl_action_goal_handle_t > rcl_goal_handle, GoalUUID uuid, std::shared_ptr< void > goal_request_message) override
Definition: server.hpp:387
GoalUUID get_goal_id_from_result_request(void *message) override
Definition: server.hpp:464
Definition: server.hpp:70
std::pair< GoalResponse, std::shared_ptr< void > > call_handle_goal_callback(GoalUUID &uuid, std::shared_ptr< void > message) override
Definition: server.hpp:342
RCLCPP_ACTION_PUBLIC bool add_to_wait_set(rcl_wait_set_t *wait_set) override
RCLCPP_ACTION_PUBLIC ServerBase(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const std::string &name, const rosidl_action_type_support_t *type_support, const rcl_action_server_options_t &options)
RCLCPP_ACTION_PUBLIC void publish_result(const GoalUUID &uuid, std::shared_ptr< void > result_msg)
std::function< void(std::shared_ptr< ServerGoalHandle< ActionT > >)> AcceptedCallback
Signature of a callback that is used to notify when the goal has been accepted.
Definition: server.hpp:283
Class to interact with goals on a server.
Definition: server_goal_handle.hpp:135