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)
183 using namespace std::placeholders;
184 action_server_ptr_ = rclcpp_action::create_server<ActionT>(
185 node_ptr_, action_name, std::bind(&ActionWrapper<ActionT>::handle_goal_,
this, _1, _2),
186 std::bind(&ActionWrapper<ActionT>::handle_cancel_,
this, _1),
187 std::bind(&ActionWrapper<ActionT>::handle_accepted_,
this, _1));
190template <
class ActionT>
192:
ActionWrapper(action_name, node_ptr, std::make_shared<ActionContextType>(node_ptr->get_logger()))
196template <
class ActionT>
198:
ActionWrapper(action_name, std::make_shared<rclcpp::Node>(action_name +
"_node", options))
202template <
class ActionT>
203rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ActionWrapper<ActionT>::get_node_base_interface()
const
205 return node_ptr_->get_node_base_interface();
208template <
class ActionT>
215template <
class ActionT>
217 std::shared_ptr<const Goal> , std::shared_ptr<Result> )
222template <
class ActionT>
224 std::shared_ptr<const Goal> , std::shared_ptr<Result> )
230template <
class ActionT>
232 std::shared_ptr<const Goal> , std::shared_ptr<Result> )
235 return ActionStatus::SUCCESS;
238template <
class ActionT>
239rclcpp_action::GoalResponse ActionWrapper<ActionT>::handle_goal_(
240 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const Goal> goal_ptr)
242 if (action_context_ptr_->isValid() && action_context_ptr_->getGoalHandlePtr()->is_active()) {
244 node_ptr_->get_logger(),
"Goal %s was REJECTED: Goal %s is still executing.",
245 rclcpp_action::to_string(uuid).c_str(),
246 rclcpp_action::to_string(action_context_ptr_->getGoalHandlePtr()->get_goal_id()).c_str());
247 return rclcpp_action::GoalResponse::REJECT;
250 if (!onGoalRequest(goal_ptr)) {
252 node_ptr_->get_logger(),
"Goal %s was REJECTED because onGoalRequest() returned false",
253 rclcpp_action::to_string(uuid).c_str());
254 return rclcpp_action::GoalResponse::REJECT;
257 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
260template <
class ActionT>
261rclcpp_action::CancelResponse ActionWrapper<ActionT>::handle_cancel_(std::shared_ptr<GoalHandle> )
263 return onCancelRequest(action_context_ptr_->getGoalHandlePtr()->get_goal(), action_context_ptr_->getResultPtr())
264 ? rclcpp_action::CancelResponse::ACCEPT
265 : rclcpp_action::CancelResponse::REJECT;
268template <
class ActionT>
269void ActionWrapper<ActionT>::handle_accepted_(std::shared_ptr<GoalHandle> goal_handle_ptr)
271 action_context_ptr_->setUp(goal_handle_ptr);
272 std::shared_ptr<const Goal> goal_ptr = action_context_ptr_->getGoalHandlePtr()->get_goal();
273 setInitialResult(goal_ptr, action_context_ptr_->getResultPtr());
274 (void)goal_handle_ptr;
276 const Params & params = param_listener_.get_params();
279 last_feedback_ts_ = node_ptr_->now() - rclcpp::Duration::from_seconds(params.feedback_rate);
282 execution_timer_ptr_ = node_ptr_->create_wall_timer(
283 std::chrono::duration<double>(params.loop_rate), [
this, goal_ptr]() { this->execution_timer_callback_(goal_ptr); });
286template <
class ActionT>
287void ActionWrapper<ActionT>::execution_timer_callback_(std::shared_ptr<const Goal> goal_ptr)
290 if (!action_context_ptr_->getGoalHandlePtr()->is_active()) {
291 execution_timer_ptr_->cancel();
296 if (action_context_ptr_->getGoalHandlePtr()->is_canceling()) {
297 switch (cancelGoal(goal_ptr, action_context_ptr_->getResultPtr())) {
298 case ActionStatus::RUNNING:
300 case ActionStatus::SUCCESS:
301 action_context_ptr_->cancel();
303 case ActionStatus::FAILURE:
304 action_context_ptr_->abort();
308 const auto ret = executeGoal(goal_ptr, action_context_ptr_->getFeedbackPtr(), action_context_ptr_->getResultPtr());
311 const auto feedback_rate = rclcpp::Duration::from_seconds(param_listener_.get_params().feedback_rate);
312 if (node_ptr_->now() - last_feedback_ts_ > feedback_rate) {
313 action_context_ptr_->publishFeedback();
314 last_feedback_ts_ = node_ptr_->now();
318 case ActionStatus::RUNNING:
320 case ActionStatus::SUCCESS:
321 action_context_ptr_->succeed();
323 case ActionStatus::FAILURE:
324 action_context_ptr_->abort();