JointStatePublisher.cpp 3.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586
  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 <ROS2/ROS2Bus.h>
  9. #include <ROS2/Utilities/ROS2Names.h>
  10. #include <ROS2Controllers/Manipulation/JointsManipulationRequests.h>
  11. #include "JointStatePublisher.h"
  12. #include "ManipulationUtils.h"
  13. namespace ROS2Controllers
  14. {
  15. JointStatePublisher::JointStatePublisher(const ROS2::PublisherConfiguration& configuration, const JointStatePublisherContext& context)
  16. : m_configuration(configuration)
  17. , m_context(context)
  18. {
  19. auto topicConfiguration = m_configuration.m_topicConfiguration;
  20. AZStd::string topic = ROS2::ROS2Names::GetNamespacedName(context.m_publisherNamespace, topicConfiguration.m_topic);
  21. auto ros2Node = ROS2::ROS2Interface::Get()->GetNode();
  22. m_jointStatePublisher = ros2Node->create_publisher<sensor_msgs::msg::JointState>(topic.data(), topicConfiguration.GetQoS());
  23. }
  24. JointStatePublisher::~JointStatePublisher()
  25. {
  26. m_eventSourceAdapter.Stop();
  27. m_adaptedEventHandler.Disconnect();
  28. }
  29. void JointStatePublisher::PublishMessage()
  30. {
  31. std_msgs::msg::Header rosHeader;
  32. rosHeader.frame_id = ROS2::ROS2Names::GetNamespacedName(m_context.m_publisherNamespace, m_context.m_frameId).data();
  33. rosHeader.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
  34. m_jointStateMsg.header = rosHeader;
  35. AZ_Assert(m_jointNames.size() == m_jointStateMsg.name.size(), "The expected message size doesn't match with the joint list size");
  36. for (size_t i = 0; i < m_jointStateMsg.name.size(); i++)
  37. {
  38. m_jointStateMsg.name[i] = m_jointNames[i].c_str();
  39. JointInfo& jointInfo = m_jointInfos[i];
  40. auto jointStateData = Utils::GetJointState(jointInfo);
  41. m_jointStateMsg.position[i] = jointStateData.position;
  42. m_jointStateMsg.velocity[i] = jointStateData.velocity;
  43. m_jointStateMsg.effort[i] = jointStateData.effort;
  44. }
  45. m_jointStatePublisher->publish(m_jointStateMsg);
  46. }
  47. void JointStatePublisher::InitializePublisher()
  48. {
  49. ManipulationJoints manipulatorJoints;
  50. JointsManipulationRequestBus::EventResult(manipulatorJoints, m_context.m_entityId, &JointsManipulationRequests::GetJoints);
  51. for (const auto& [jointName, jointInfo] : manipulatorJoints)
  52. {
  53. m_jointNames.push_back(jointName);
  54. m_jointInfos.push_back(jointInfo);
  55. }
  56. m_jointStateMsg.name.resize(manipulatorJoints.size());
  57. m_jointStateMsg.position.resize(manipulatorJoints.size());
  58. m_jointStateMsg.velocity.resize(manipulatorJoints.size());
  59. m_jointStateMsg.effort.resize(manipulatorJoints.size());
  60. m_eventSourceAdapter.SetFrequency(m_configuration.m_frequency);
  61. m_adaptedEventHandler = decltype(m_adaptedEventHandler)(
  62. [this](auto&&... args)
  63. {
  64. if (!m_configuration.m_publish)
  65. {
  66. return;
  67. }
  68. PublishMessage();
  69. });
  70. m_eventSourceAdapter.ConnectToAdaptedEvent(m_adaptedEventHandler);
  71. m_eventSourceAdapter.Start();
  72. }
  73. } // namespace ROS2Controllers