122 virtual bool onCancelRequest(std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Result> result_ptr);
135 virtual Status
cancelGoal(std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Result> result_ptr);
148 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr,
149 std::shared_ptr<Result> result_ptr) = 0;
155 rclcpp_action::GoalResponse handle_goal_(
const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const Goal> goal_ptr);
156 rclcpp_action::CancelResponse handle_cancel_(std::shared_ptr<GoalHandle> goal_handle_ptr);
157 void handle_accepted_(std::shared_ptr<GoalHandle> goal_handle_ptr);
159 void execution_timer_callback_(std::shared_ptr<const Goal> goal_ptr);
162 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
const;
165 rclcpp::Node::SharedPtr node_ptr_;
166 std::shared_ptr<ActionContextType> action_context_ptr_;
167 const ParamListener param_listener_;
170 typename rclcpp_action::Server<ActionT>::SharedPtr action_server_ptr_;
171 rclcpp::TimerBase::SharedPtr execution_timer_ptr_;
172 rclcpp::Time last_feedback_ts_;
175template <
class ActionT>
177 const std::string & action_name, rclcpp::Node::SharedPtr node_ptr,
178 std::shared_ptr<ActionContextType> action_context_ptr)
179: node_ptr_(node_ptr), action_context_ptr_(action_context_ptr), param_listener_(node_ptr)
181 using namespace std::placeholders;
182 action_server_ptr_ = rclcpp_action::create_server<ActionT>(
183 node_ptr_, action_name, std::bind(&ActionWrapper<ActionT>::handle_goal_,
this, _1, _2),
184 std::bind(&ActionWrapper<ActionT>::handle_cancel_,
this, _1),
185 std::bind(&ActionWrapper<ActionT>::handle_accepted_,
this, _1));
188template <
class ActionT>
190:
ActionWrapper(action_name, node_ptr, std::make_shared<ActionContextType>(node_ptr->get_logger()))
194template <
class ActionT>
196:
ActionWrapper(action_name, std::make_shared<rclcpp::Node>(action_name +
"_node", options))
200template <
class ActionT>
201rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ActionWrapper<ActionT>::get_node_base_interface()
const
203 return node_ptr_->get_node_base_interface();
206template <
class ActionT>
213template <
class ActionT>
215 std::shared_ptr<const Goal> , std::shared_ptr<Result> )
220template <
class ActionT>
222 std::shared_ptr<const Goal> , std::shared_ptr<Result> )
228template <
class ActionT>
230 std::shared_ptr<const Goal> , std::shared_ptr<Result> )
233 return ActionStatus::SUCCESS;
236template <
class ActionT>
237rclcpp_action::GoalResponse ActionWrapper<ActionT>::handle_goal_(
238 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const Goal> goal_ptr)
240 if (action_context_ptr_->isValid() && action_context_ptr_->getGoalHandlePtr()->is_active()) {
242 node_ptr_->get_logger(),
"Goal %s was REJECTED: Goal %s is still executing.",
243 rclcpp_action::to_string(uuid).c_str(),
244 rclcpp_action::to_string(action_context_ptr_->getGoalHandlePtr()->get_goal_id()).c_str());
245 return rclcpp_action::GoalResponse::REJECT;
248 if (!onGoalRequest(goal_ptr)) {
250 node_ptr_->get_logger(),
"Goal %s was REJECTED because onGoalRequest() returned false",
251 rclcpp_action::to_string(uuid).c_str());
252 return rclcpp_action::GoalResponse::REJECT;
255 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
258template <
class ActionT>
259rclcpp_action::CancelResponse ActionWrapper<ActionT>::handle_cancel_(std::shared_ptr<GoalHandle> )
261 return onCancelRequest(action_context_ptr_->getGoalHandlePtr()->get_goal(), action_context_ptr_->getResultPtr())
262 ? rclcpp_action::CancelResponse::ACCEPT
263 : rclcpp_action::CancelResponse::REJECT;
266template <
class ActionT>
267void ActionWrapper<ActionT>::handle_accepted_(std::shared_ptr<GoalHandle> goal_handle_ptr)
269 action_context_ptr_->setUp(goal_handle_ptr);
270 std::shared_ptr<const Goal> goal_ptr = action_context_ptr_->getGoalHandlePtr()->get_goal();
271 setInitialResult(goal_ptr, action_context_ptr_->getResultPtr());
272 (void)goal_handle_ptr;
274 const Params & params = param_listener_.get_params();
277 last_feedback_ts_ = node_ptr_->now() - rclcpp::Duration::from_seconds(params.feedback_rate);
280 execution_timer_ptr_ = node_ptr_->create_wall_timer(
281 std::chrono::duration<double>(params.loop_rate), [
this, goal_ptr]() { this->execution_timer_callback_(goal_ptr); });
284template <
class ActionT>
285void ActionWrapper<ActionT>::execution_timer_callback_(std::shared_ptr<const Goal> goal_ptr)
288 if (!action_context_ptr_->getGoalHandlePtr()->is_active()) {
289 execution_timer_ptr_->cancel();
294 if (action_context_ptr_->getGoalHandlePtr()->is_canceling()) {
295 switch (cancelGoal(goal_ptr, action_context_ptr_->getResultPtr())) {
296 case ActionStatus::RUNNING:
298 case ActionStatus::SUCCESS:
299 action_context_ptr_->cancel();
301 case ActionStatus::FAILURE:
302 action_context_ptr_->abort();
306 const auto ret = executeGoal(goal_ptr, action_context_ptr_->getFeedbackPtr(), action_context_ptr_->getResultPtr());
309 const auto feedback_rate = rclcpp::Duration::from_seconds(param_listener_.get_params().feedback_rate);
310 if (node_ptr_->now() - last_feedback_ts_ > feedback_rate) {
311 action_context_ptr_->publishFeedback();
312 last_feedback_ts_ = node_ptr_->now();
316 case ActionStatus::RUNNING:
318 case ActionStatus::SUCCESS:
319 action_context_ptr_->succeed();
321 case ActionStatus::FAILURE:
322 action_context_ptr_->abort();