/* * Copyright (c) Contributors to the Open 3D Engine Project. * For complete copyright and license terms please see the LICENSE at the root * of this distribution. * * SPDX-License-Identifier: Apache-2.0 OR MIT * */ #pragma once #include #include #include #include #include #include namespace ROS2Controllers { //! GripperActionServer is a class responsible for managing an action server controlling a gripper //! @see ROS 2 action //! server documentation //! @see GripperCommand documentation class GripperActionServer { public: using GripperCommand = control_msgs::action::GripperCommand; using GoalHandleGripperCommand = rclcpp_action::ServerGoalHandle; //! Create an action server for GripperAction action and bind Goal callbacks. //! @param actionName Name of the action, similar to topic or service name. //! @param entityId entity which will execute callbacks through GripperRequestBus. GripperActionServer(const AZStd::string& actionName, const AZ::EntityId& entityId); //! Cancel the current goal. //! @param result Result to be passed to through action server to the client. void CancelGoal(std::shared_ptr result); //! Report goal success to the action server. //! @param result Result which contains success code. void GoalSuccess(std::shared_ptr result); //! Publish feedback during an active action. //! @param feedback An action feedback message informing about the progress. void PublishFeedback(std::shared_ptr feedback); //! Check if the goal is in an active state bool IsGoalActiveState() const; //! Check if the goal is in a pending state bool IsReadyForExecution() const; private: rclcpp_action::GoalResponse GoalReceivedCallback( const rclcpp_action::GoalUUID& uuid, std::shared_ptr goal); rclcpp_action::CancelResponse GoalCancelledCallback(const std::shared_ptr goal_handle); void GoalAcceptedCallback(const std::shared_ptr goal_handle); rclcpp_action::Server::SharedPtr actionServer; std::shared_ptr m_goalHandle; AZ::EntityId m_entityId; //! Entity that has target gripper component }; } // namespace ROS2Controllers