GripperActionServer.cpp 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130
  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
  4. * of this distribution.
  5. *
  6. * SPDX-License-Identifier: Apache-2.0 OR MIT
  7. *
  8. */
  9. #include "Utils.h"
  10. #include "GripperActionServer.h"
  11. #include <AzCore/Serialization/EditContext.h>
  12. #include <AzCore/Serialization/SerializeContext.h>
  13. #include <AzFramework/Components/TransformComponent.h>
  14. #include <ROS2/ROS2Bus.h>
  15. namespace ROS2Controllers
  16. {
  17. GripperActionServer::GripperActionServer(const AZStd::string& actionName, const AZ::EntityId& entityId)
  18. : m_entityId(entityId)
  19. {
  20. auto ros2Node = ROS2::ROS2Interface::Get()->GetNode();
  21. actionServer = rclcpp_action::create_server<GripperCommand>(
  22. ros2Node,
  23. actionName.data(),
  24. AZStd::bind(&GripperActionServer::GoalReceivedCallback, this, AZStd::placeholders::_1, AZStd::placeholders::_2),
  25. AZStd::bind(&GripperActionServer::GoalCancelledCallback, this, AZStd::placeholders::_1),
  26. AZStd::bind(&GripperActionServer::GoalAcceptedCallback, this, AZStd::placeholders::_1));
  27. }
  28. bool GripperActionServer::IsGoalActiveState() const
  29. {
  30. if (!m_goalHandle)
  31. {
  32. return false;
  33. }
  34. return m_goalHandle->is_active() || m_goalHandle->is_executing() || m_goalHandle->is_canceling();
  35. }
  36. bool GripperActionServer::IsReadyForExecution() const
  37. {
  38. // Has no goal handle yet - can be accepted.
  39. if (!m_goalHandle)
  40. {
  41. return true;
  42. }
  43. // Accept if the previous one is in a terminal state.
  44. return IsGoalActiveState() == false;
  45. }
  46. rclcpp_action::GoalResponse GripperActionServer::GoalReceivedCallback(
  47. [[maybe_unused]] const rclcpp_action::GoalUUID& uuid, std::shared_ptr<const GripperCommand::Goal> goal)
  48. {
  49. if (!IsReadyForExecution())
  50. {
  51. AZ_Printf("GripperActionServer", "GripperActionServer::handleGoal: Rejected goal, already executing\n");
  52. if (m_goalHandle)
  53. {
  54. AZ_Trace(
  55. "GripperActionServer",
  56. " is_active: %d, is_executing %d, is_canceling : %d\n",
  57. m_goalHandle->is_active(),
  58. m_goalHandle->is_executing(),
  59. m_goalHandle->is_canceling());
  60. }
  61. return rclcpp_action::GoalResponse::REJECT;
  62. }
  63. AZ::Outcome<void, AZStd::string> commandOutcome = AZ::Failure(AZStd::string("No gripper component found!"));
  64. GripperRequestBus::EventResult(
  65. commandOutcome, m_entityId, &GripperRequestBus::Events::GripperCommand, goal->command.position, goal->command.max_effort);
  66. if (!commandOutcome.IsSuccess())
  67. {
  68. AZ_Trace("GripperActionServer", "GripperCommand could not be accepted: %s\n", commandOutcome.GetError().c_str());
  69. return rclcpp_action::GoalResponse::REJECT;
  70. }
  71. AZ_Trace("GripperActionServer", "GripperActionServer::handleGoal: GripperCommand accepted!\n");
  72. return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
  73. }
  74. rclcpp_action::CancelResponse GripperActionServer::GoalCancelledCallback(const std::shared_ptr<GoalHandleGripperCommand> goal_handle)
  75. {
  76. AZ::Outcome<void, AZStd::string> cancelOutcome = AZ::Failure(AZStd::string("No gripper component found!"));
  77. GripperRequestBus::EventResult(cancelOutcome, m_entityId, &GripperRequestBus::Events::CancelGripperCommand);
  78. if (!cancelOutcome)
  79. { // This will not happen in a simulation unless intentionally done for behavior validation
  80. AZ_Trace("GripperActionServer", "Cancelling could not be accepted: %s\n", cancelOutcome.GetError().c_str());
  81. return rclcpp_action::CancelResponse::REJECT;
  82. }
  83. return rclcpp_action::CancelResponse::ACCEPT;
  84. }
  85. void GripperActionServer::GoalAcceptedCallback(const std::shared_ptr<GoalHandleGripperCommand> goal_handle)
  86. {
  87. AZ_Trace("GripperActionServer", "Goal accepted!\n");
  88. m_goalHandle = goal_handle;
  89. }
  90. void GripperActionServer::CancelGoal(std::shared_ptr<GripperCommand::Result> result)
  91. {
  92. AZ_Assert(m_goalHandle, "Invalid goal handle!");
  93. if (m_goalHandle && m_goalHandle->is_canceling())
  94. {
  95. AZ_Trace("GripperActionServer", "Cancelling goal\n");
  96. m_goalHandle->canceled(result);
  97. }
  98. }
  99. void GripperActionServer::GoalSuccess(std::shared_ptr<GripperCommand::Result> result)
  100. {
  101. AZ_Assert(m_goalHandle, "Invalid goal handle!");
  102. if (m_goalHandle && (m_goalHandle->is_executing() || m_goalHandle->is_canceling()))
  103. {
  104. AZ_Trace("GripperActionServer", "Goal succeeded\n");
  105. m_goalHandle->succeed(result);
  106. }
  107. }
  108. void GripperActionServer::PublishFeedback(std::shared_ptr<GripperCommand::Feedback> feedback)
  109. {
  110. AZ_Assert(m_goalHandle, "Invalid goal handle!");
  111. if (m_goalHandle && m_goalHandle->is_executing())
  112. {
  113. m_goalHandle->publish_feedback(feedback);
  114. }
  115. }
  116. } // namespace ROS2Controllers