JointsManipulationComponent.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444
  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. #include "JointsManipulationComponent.h"
  9. #include "Controllers/JointsArticulationControllerComponent.h"
  10. #include "Controllers/JointsPIDControllerComponent.h"
  11. #include "JointStatePublisher.h"
  12. #include "ManipulationUtils.h"
  13. #include <AzCore/Component/ComponentApplicationBus.h>
  14. #include <AzCore/Component/TransformBus.h>
  15. #include <AzCore/Debug/Trace.h>
  16. #include <AzCore/Serialization/EditContext.h>
  17. #include <ROS2/Clock/ROS2ClockRequestBus.h>
  18. #include <ROS2/Frame/ROS2FrameComponent.h>
  19. #include <ROS2/Utilities/ROS2Conversions.h>
  20. #include <ROS2Controllers/Manipulation/Controllers/JointsPositionControllerRequests.h>
  21. #include <Source/ArticulationLinkComponent.h>
  22. #include <Source/HingeJointComponent.h>
  23. #include <Source/PrismaticJointComponent.h>
  24. #include <Utilities/ArticulationsUtilities.h>
  25. namespace ROS2Controllers
  26. {
  27. namespace Internal
  28. {
  29. void Add1DOFJointInfo(const AZ::EntityComponentIdPair& idPair, const AZStd::string& jointName, ManipulationJoints& joints)
  30. {
  31. if (joints.find(jointName) != joints.end())
  32. {
  33. AZ_Assert(false, "Joint names in hierarchy need to be unique (%s is not)!", jointName.c_str());
  34. return;
  35. }
  36. JointInfo jointInfo;
  37. jointInfo.m_isArticulation = false;
  38. jointInfo.m_axis = static_cast<PhysX::ArticulationJointAxis>(0);
  39. jointInfo.m_entityComponentIdPair = idPair;
  40. joints[jointName] = jointInfo;
  41. }
  42. void AddArticulationJointInfo(const AZ::EntityComponentIdPair& idPair, const AZStd::string& jointName, ManipulationJoints& joints)
  43. {
  44. bool isRoot = false;
  45. PhysX::ArticulationJointRequestBus::EventResult(
  46. isRoot, idPair.GetEntityId(), &PhysX::ArticulationJointRequests::IsRootArticulation);
  47. if (isRoot)
  48. { // Root articulation does not have a joint
  49. return;
  50. }
  51. const auto freeAxis = Utils::TryGetFreeArticulationAxis(idPair.GetEntityId());
  52. if (!freeAxis.has_value())
  53. { // Do not add a joint since it is a fixed one
  54. return;
  55. }
  56. if (joints.find(jointName) != joints.end())
  57. {
  58. AZ_Error(
  59. "JointsManipulationComponent", false, "Joint names in hierarchy need to be unique (%s is not)!", jointName.c_str());
  60. return;
  61. }
  62. JointInfo jointInfo;
  63. jointInfo.m_isArticulation = true;
  64. jointInfo.m_axis = freeAxis.value();
  65. jointInfo.m_entityComponentIdPair = idPair;
  66. joints[jointName] = jointInfo;
  67. }
  68. ManipulationJoints GetAllEntityHierarchyJoints(const AZ::EntityId& entityId)
  69. { // Look for either Articulation Links or Hinge joints in entity hierarchy and collect them into a map.
  70. // Determine kind of joints through presence of appropriate controller
  71. bool supportsArticulation = false;
  72. bool supportsClassicJoints = false;
  73. JointsPositionControllerRequestBus::EventResult(
  74. supportsArticulation, entityId, &JointsPositionControllerRequests::SupportsArticulation);
  75. JointsPositionControllerRequestBus::EventResult(
  76. supportsClassicJoints, entityId, &JointsPositionControllerRequests::SupportsClassicJoints);
  77. ManipulationJoints manipulationJoints;
  78. if (!supportsArticulation && !supportsClassicJoints)
  79. {
  80. AZ_Warning("JointsManipulationComponent", false, "No suitable Position Controller Component in entity!");
  81. return manipulationJoints;
  82. }
  83. if (supportsArticulation && supportsClassicJoints)
  84. {
  85. AZ_Warning("JointsManipulationComponent", false, "Cannot support both classic joint and articulations in one hierarchy");
  86. return manipulationJoints;
  87. }
  88. // Get all descendants and iterate over joints
  89. AZStd::vector<AZ::EntityId> descendants;
  90. AZ::TransformBus::EventResult(descendants, entityId, &AZ::TransformInterface::GetEntityAndAllDescendants);
  91. AZ_Warning("JointsManipulationComponent", descendants.size() > 0, "Entity %s has no descendants!", entityId.ToString().c_str());
  92. for (const AZ::EntityId& descendantID : descendants)
  93. {
  94. AZ::Entity* entity = nullptr;
  95. AZ::ComponentApplicationBus::BroadcastResult(entity, &AZ::ComponentApplicationRequests::FindEntity, descendantID);
  96. AZ_Assert(entity, "Unknown entity %s", descendantID.ToString().c_str());
  97. // If there is a Frame Component, take joint name stored in it.
  98. auto* frameComponent = entity->FindComponent<ROS2::ROS2FrameComponent>();
  99. if (!frameComponent)
  100. { // Frame Component is required for joints.
  101. continue;
  102. }
  103. const AZStd::string jointName(frameComponent->GetJointName().c_str());
  104. auto* hingeComponent = entity->FindComponent<PhysX::HingeJointComponent>();
  105. auto* prismaticComponent = entity->FindComponent<PhysX::PrismaticJointComponent>();
  106. auto* articulationComponent = entity->FindComponent<PhysX::ArticulationLinkComponent>();
  107. [[maybe_unused]] bool classicJoint = hingeComponent || prismaticComponent;
  108. AZ_Warning(
  109. "JointsManipulationComponent",
  110. (classicJoint && supportsClassicJoints) || !classicJoint,
  111. "Found classic joints but the controller does not support them!");
  112. AZ_Warning(
  113. "JointsManipulationComponent",
  114. (articulationComponent && supportsArticulation) || !articulationComponent,
  115. "Found articulations but the controller does not support them!");
  116. // See if there is a Hinge Joint in the entity, add it to map.
  117. if (supportsClassicJoints && hingeComponent)
  118. {
  119. auto idPair = AZ::EntityComponentIdPair(hingeComponent->GetEntityId(), hingeComponent->GetId());
  120. Internal::Add1DOFJointInfo(idPair, jointName, manipulationJoints);
  121. }
  122. // See if there is a Prismatic Joint in the entity, add it to map.
  123. if (supportsClassicJoints && prismaticComponent)
  124. {
  125. auto idPair = AZ::EntityComponentIdPair(prismaticComponent->GetEntityId(), prismaticComponent->GetId());
  126. Internal::Add1DOFJointInfo(idPair, jointName, manipulationJoints);
  127. }
  128. // See if there is an Articulation Link in the entity, add it to map.
  129. if (supportsArticulation && articulationComponent)
  130. {
  131. auto idPair = AZ::EntityComponentIdPair(articulationComponent->GetEntityId(), articulationComponent->GetId());
  132. Internal::AddArticulationJointInfo(idPair, jointName, manipulationJoints);
  133. }
  134. }
  135. return manipulationJoints;
  136. }
  137. void SetInitialPositions(
  138. ManipulationJoints& manipulationJoints, const AZStd::vector<AZStd::pair<AZStd::string, float>>& initialPositions)
  139. {
  140. // Set the initial / resting position to move to and keep.
  141. for (const auto& [jointName, position] : initialPositions)
  142. {
  143. if (manipulationJoints.contains(jointName))
  144. {
  145. manipulationJoints[jointName].m_restPosition = position;
  146. }
  147. else
  148. {
  149. AZ_Warning("JointsManipulationComponent", false, "No joint %s to set initial position", jointName.c_str());
  150. }
  151. }
  152. }
  153. } // namespace Internal
  154. JointsManipulationComponent::JointsManipulationComponent()
  155. {
  156. }
  157. JointsManipulationComponent::JointsManipulationComponent(
  158. const ROS2::PublisherConfiguration& publisherConfiguration,
  159. const AZStd::vector<AZStd::pair<AZStd::string, float>>& initialPositions)
  160. : m_jointStatePublisherConfiguration(publisherConfiguration)
  161. , m_initialPositions(initialPositions)
  162. {
  163. }
  164. void JointsManipulationComponent::Activate()
  165. {
  166. auto* ros2Frame = GetEntity()->FindComponent<ROS2::ROS2FrameComponent>();
  167. JointStatePublisherContext publisherContext;
  168. publisherContext.m_publisherNamespace = ros2Frame->GetNamespace();
  169. publisherContext.m_frameId = ros2Frame->GetNamespacedFrameID();
  170. publisherContext.m_entityId = GetEntityId();
  171. m_jointStatePublisher = AZStd::make_unique<JointStatePublisher>(m_jointStatePublisherConfiguration, publisherContext);
  172. ROS2::ROS2ClockRequestBus::BroadcastResult(m_lastTickTimestamp, &ROS2::ROS2ClockRequestBus::Events::GetROSTimestamp);
  173. AZ::TickBus::Handler::BusConnect();
  174. JointsManipulationRequestBus::Handler::BusConnect(GetEntityId());
  175. }
  176. void JointsManipulationComponent::Deactivate()
  177. {
  178. JointsManipulationRequestBus::Handler::BusDisconnect();
  179. AZ::TickBus::Handler::BusDisconnect();
  180. }
  181. ManipulationJoints JointsManipulationComponent::GetJoints()
  182. {
  183. return m_manipulationJoints;
  184. }
  185. AZ::Outcome<JointPosition, AZStd::string> JointsManipulationComponent::GetJointPosition(const JointInfo& jointInfo)
  186. {
  187. float position{ 0.f };
  188. if (jointInfo.m_isArticulation)
  189. {
  190. PhysX::ArticulationJointRequestBus::EventResult(
  191. position,
  192. jointInfo.m_entityComponentIdPair.GetEntityId(),
  193. &PhysX::ArticulationJointRequests::GetJointPosition,
  194. jointInfo.m_axis);
  195. }
  196. else
  197. {
  198. PhysX::JointRequestBus::EventResult(position, jointInfo.m_entityComponentIdPair, &PhysX::JointRequests::GetPosition);
  199. }
  200. return AZ::Success(position);
  201. }
  202. AZ::Outcome<JointPosition, AZStd::string> JointsManipulationComponent::GetJointPosition(const AZStd::string& jointName)
  203. {
  204. if (!m_manipulationJoints.contains(jointName))
  205. {
  206. return AZ::Failure(AZStd::string::format("Joint %s does not exist", jointName.c_str()));
  207. }
  208. auto jointInfo = m_manipulationJoints.at(jointName);
  209. return GetJointPosition(jointInfo);
  210. }
  211. AZ::Outcome<JointVelocity, AZStd::string> JointsManipulationComponent::GetJointVelocity(const JointInfo& jointInfo)
  212. {
  213. float velocity{ 0.f };
  214. if (jointInfo.m_isArticulation)
  215. {
  216. PhysX::ArticulationJointRequestBus::EventResult(
  217. velocity,
  218. jointInfo.m_entityComponentIdPair.GetEntityId(),
  219. &PhysX::ArticulationJointRequests::GetJointVelocity,
  220. jointInfo.m_axis);
  221. }
  222. else
  223. {
  224. PhysX::JointRequestBus::EventResult(velocity, jointInfo.m_entityComponentIdPair, &PhysX::JointRequests::GetVelocity);
  225. }
  226. return AZ::Success(velocity);
  227. }
  228. AZ::Outcome<JointVelocity, AZStd::string> JointsManipulationComponent::GetJointVelocity(const AZStd::string& jointName)
  229. {
  230. if (!m_manipulationJoints.contains(jointName))
  231. {
  232. return AZ::Failure(AZStd::string::format("Joint %s does not exist", jointName.c_str()));
  233. }
  234. auto jointInfo = m_manipulationJoints.at(jointName);
  235. return GetJointVelocity(jointInfo);
  236. }
  237. JointsManipulationRequests::JointsPositionsMap JointsManipulationComponent::GetAllJointsPositions()
  238. {
  239. JointsManipulationRequests::JointsPositionsMap positions;
  240. for (const auto& [jointName, jointInfo] : m_manipulationJoints)
  241. {
  242. positions[jointName] = GetJointPosition(jointInfo).GetValue();
  243. }
  244. return positions;
  245. }
  246. JointsManipulationRequests::JointsVelocitiesMap JointsManipulationComponent::GetAllJointsVelocities()
  247. {
  248. JointsManipulationRequests::JointsVelocitiesMap velocities;
  249. for (const auto& [jointName, jointInfo] : m_manipulationJoints)
  250. {
  251. velocities[jointName] = GetJointVelocity(jointInfo).GetValue();
  252. }
  253. return velocities;
  254. }
  255. AZ::Outcome<JointEffort, AZStd::string> JointsManipulationComponent::GetJointEffort(const JointInfo& jointInfo)
  256. {
  257. auto jointStateData = Utils::GetJointState(jointInfo);
  258. return AZ::Success(jointStateData.effort);
  259. }
  260. AZ::Outcome<JointEffort, AZStd::string> JointsManipulationComponent::GetJointEffort(const AZStd::string& jointName)
  261. {
  262. if (!m_manipulationJoints.contains(jointName))
  263. {
  264. return AZ::Failure(AZStd::string::format("Joint %s does not exist", jointName.c_str()));
  265. }
  266. auto jointInfo = m_manipulationJoints.at(jointName);
  267. return GetJointEffort(jointInfo);
  268. }
  269. JointsManipulationRequests::JointsEffortsMap JointsManipulationComponent::GetAllJointsEfforts()
  270. {
  271. JointsManipulationRequests::JointsEffortsMap efforts;
  272. for (const auto& [jointName, jointInfo] : m_manipulationJoints)
  273. {
  274. efforts[jointName] = GetJointEffort(jointInfo).GetValue();
  275. }
  276. return efforts;
  277. }
  278. AZ::Outcome<void, AZStd::string> JointsManipulationComponent::SetMaxJointEffort(const AZStd::string& jointName, JointEffort maxEffort)
  279. {
  280. if (!m_manipulationJoints.contains(jointName))
  281. {
  282. return AZ::Failure(AZStd::string::format("Joint %s does not exist", jointName.c_str()));
  283. }
  284. auto jointInfo = m_manipulationJoints.at(jointName);
  285. if (jointInfo.m_isArticulation)
  286. {
  287. PhysX::ArticulationJointRequestBus::Event(
  288. jointInfo.m_entityComponentIdPair.GetEntityId(),
  289. &PhysX::ArticulationJointRequests::SetMaxForce,
  290. jointInfo.m_axis,
  291. maxEffort);
  292. }
  293. return AZ::Success();
  294. }
  295. AZ::Outcome<void, AZStd::string> JointsManipulationComponent::MoveJointToPosition(
  296. const AZStd::string& jointName, JointPosition position)
  297. {
  298. if (!m_manipulationJoints.contains(jointName))
  299. {
  300. return AZ::Failure(AZStd::string::format("Joint %s does not exist", jointName.c_str()));
  301. }
  302. m_manipulationJoints[jointName].m_restPosition = position;
  303. return AZ::Success();
  304. }
  305. AZ::Outcome<void, AZStd::string> JointsManipulationComponent::MoveJointsToPositions(
  306. const JointsManipulationRequests::JointsPositionsMap& positions)
  307. {
  308. for (const auto& [jointName, position] : positions)
  309. {
  310. auto outcome = MoveJointToPosition(jointName, position);
  311. if (!outcome)
  312. {
  313. return outcome;
  314. }
  315. }
  316. return AZ::Success();
  317. }
  318. void JointsManipulationComponent::GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required)
  319. {
  320. required.push_back(AZ_CRC_CE("ROS2Frame"));
  321. required.push_back(AZ_CRC_CE("JointsControllerService"));
  322. }
  323. void JointsManipulationComponent::GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided)
  324. {
  325. provided.push_back(AZ_CRC_CE("JointsManipulationService"));
  326. }
  327. void JointsManipulationComponent::GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible)
  328. {
  329. incompatible.push_back(AZ_CRC_CE("JointsManipulationService"));
  330. }
  331. void JointsManipulationComponent::Reflect(AZ::ReflectContext* context)
  332. {
  333. if (AZ::SerializeContext* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  334. {
  335. serialize->Class<JointsManipulationComponent, AZ::Component>()
  336. ->Version(2)
  337. ->Field("JointStatesPublisherConfiguration", &JointsManipulationComponent::m_jointStatePublisherConfiguration)
  338. ->Field("OrderedInitialJointPositions", &JointsManipulationComponent::m_initialPositions);
  339. }
  340. }
  341. void JointsManipulationComponent::MoveToSetPositions(float deltaTime)
  342. {
  343. for (const auto& [jointName, jointInfo] : m_manipulationJoints)
  344. {
  345. float currentPosition = GetJointPosition(jointName).GetValue();
  346. float desiredPosition = jointInfo.m_restPosition;
  347. AZ::Outcome<void, AZStd::string> positionControlOutcome;
  348. JointsPositionControllerRequestBus::EventResult(
  349. positionControlOutcome,
  350. GetEntityId(),
  351. &JointsPositionControllerRequests::PositionControl,
  352. jointName,
  353. jointInfo,
  354. currentPosition,
  355. desiredPosition,
  356. deltaTime);
  357. AZ_Warning(
  358. "JointsManipulationComponent",
  359. positionControlOutcome,
  360. "Position control failed for joint %s (%s): %s",
  361. jointName.c_str(),
  362. jointInfo.m_entityComponentIdPair.GetEntityId().ToString().c_str(),
  363. positionControlOutcome.GetError().c_str());
  364. }
  365. }
  366. void JointsManipulationComponent::Stop()
  367. {
  368. for (auto& [jointName, jointInfo] : m_manipulationJoints)
  369. { // Set all target joint positions to their current positions. There is no need to check if the outcome is successful, because
  370. // jointName is always valid.
  371. jointInfo.m_restPosition = GetJointPosition(jointName).GetValue();
  372. }
  373. }
  374. void JointsManipulationComponent::OnTick([[maybe_unused]] float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time)
  375. {
  376. if (m_manipulationJoints.empty())
  377. {
  378. m_manipulationJoints = Internal::GetAllEntityHierarchyJoints(GetEntityId());
  379. Internal::SetInitialPositions(m_manipulationJoints, m_initialPositions);
  380. if (m_manipulationJoints.empty())
  381. {
  382. AZ_Warning("JointsManipulationComponent", false, "No manipulation joints to handle!");
  383. AZ::TickBus::Handler::BusDisconnect();
  384. return;
  385. }
  386. m_jointStatePublisher->InitializePublisher();
  387. }
  388. builtin_interfaces::msg::Time simTimestamp;
  389. ROS2::ROS2ClockRequestBus::BroadcastResult(simTimestamp, &ROS2::ROS2ClockRequestBus::Events::GetROSTimestamp);
  390. float deltaSimTime = ROS2::ROS2Conversions::GetTimeDifference(m_lastTickTimestamp, simTimestamp);
  391. MoveToSetPositions(deltaSimTime);
  392. m_lastTickTimestamp = simTimestamp;
  393. }
  394. } // namespace ROS2Controllers