JointsTrajectoryComponent.h 3.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273
  1. /*
  2. * Copyright (c) Contributors to the Open 3D Engine Project.
  3. * For complete copyright and license terms please see the LICENSE at the root of this distribution.
  4. *
  5. * SPDX-License-Identifier: Apache-2.0 OR MIT
  6. *
  7. */
  8. #pragma once
  9. #include "FollowJointTrajectoryActionServer.h"
  10. #include <AzCore/Component/Component.h>
  11. #include <AzCore/Component/EntityBus.h>
  12. #include <AzCore/Component/TickBus.h>
  13. #include <ROS2Controllers/Manipulation/JointsManipulationRequests.h>
  14. #include <ROS2Controllers/Manipulation/JointsTrajectoryRequests.h>
  15. #include <ROS2Controllers/ROS2ControllersTypeIds.h>
  16. #include <control_msgs/action/follow_joint_trajectory.hpp>
  17. namespace ROS2Controllers
  18. {
  19. //! Component responsible for execution of commands to move robotic arm (manipulator) based on set trajectory goal.
  20. class JointsTrajectoryComponent
  21. : public AZ::Component
  22. , public AZ::TickBus::Handler
  23. , public JointsTrajectoryRequestBus::Handler
  24. {
  25. public:
  26. JointsTrajectoryComponent() = default;
  27. JointsTrajectoryComponent(const AZStd::string& followTrajectoryActionName);
  28. ~JointsTrajectoryComponent() = default;
  29. AZ_COMPONENT(JointsTrajectoryComponent, JointsTrajectoryComponentTypeId, AZ::Component);
  30. static void GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required);
  31. static void GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided);
  32. static void GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible);
  33. static void Reflect(AZ::ReflectContext* context);
  34. // JointsTrajectoryRequestBus::Handler overrides ...
  35. //! @see ROS2::JointsTrajectoryRequestBus::StartTrajectoryGoal
  36. AZ::Outcome<void, TrajectoryResult> StartTrajectoryGoal(TrajectoryGoalPtr trajectoryGoal) override;
  37. //! @see ROS2::JointsTrajectoryRequestBus::CancelTrajectoryGoal
  38. AZ::Outcome<void, AZStd::string> CancelTrajectoryGoal() override;
  39. //! @see ROS2::JointsTrajectoryRequestBus::GetGoalStatus
  40. TrajectoryActionStatus GetGoalStatus() override;
  41. private:
  42. // Component overrides ...
  43. void Activate() override;
  44. void Deactivate() override;
  45. // AZ::TickBus::Handler overrides
  46. void OnTick(float deltaTime, AZ::ScriptTimePoint time) override;
  47. //! Follow set trajectory.
  48. //! @param deltaTimeNs frame time step, to advance trajectory by.
  49. void FollowTrajectory(const uint64_t deltaTimeNs);
  50. AZ::Outcome<void, TrajectoryResult> ValidateGoal(TrajectoryGoalPtr trajectoryGoal);
  51. void MoveToNextPoint(const trajectory_msgs::msg::JointTrajectoryPoint currentTrajectoryPoint);
  52. void UpdateFeedback();
  53. //! Lazy initialize Manipulation joints on the start of simulation.
  54. ManipulationJoints& GetManipulationJoints();
  55. AZStd::string m_followTrajectoryActionName{ "arm_controller/follow_joint_trajectory" };
  56. AZStd::unique_ptr<FollowJointTrajectoryActionServer> m_followTrajectoryServer;
  57. TrajectoryGoal m_trajectoryGoal;
  58. TrajectoryActionStatus m_goalStatus = TrajectoryActionStatus::Idle;
  59. rclcpp::Time m_trajectoryExecutionStartTime;
  60. ManipulationJoints m_manipulationJoints;
  61. builtin_interfaces::msg::Time m_lastTickTimestamp; //!< ROS 2 Timestamp during last OnTick call
  62. };
  63. } // namespace ROS2Controllers