/* * 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 { //! A class wrapping ROS 2 action server for joint trajectory controller. //! @see joint trajectory //! controller . class FollowJointTrajectoryActionServer { public: using FollowJointTrajectory = control_msgs::action::FollowJointTrajectory; //! Create an action server for FollowJointTrajectory 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 JointsTrajectoryRequestBus. //! @see ROS 2 action //! server documentation FollowJointTrajectoryActionServer(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); private: using GoalHandle = rclcpp_action::ServerGoalHandle; using TrajectoryActionStatus = JointsTrajectoryRequests::TrajectoryActionStatus; AZ::EntityId m_entityId; rclcpp_action::Server::SharedPtr m_actionServer; std::shared_ptr m_goalHandle; bool IsGoalActiveState() const; bool IsReadyForExecution() const; bool IsExecuting() const; rclcpp_action::GoalResponse GoalReceivedCallback( const rclcpp_action::GoalUUID& uuid, std::shared_ptr goal); rclcpp_action::CancelResponse GoalCancelledCallback(const std::shared_ptr goalHandle); void GoalAcceptedCallback(const std::shared_ptr goalHandle); }; } // namespace ROS2Controllers