ROS2OdometrySensorComponent.cpp 6.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134
  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 "ROS2OdometrySensorComponent.h"
  9. #include <AzFramework/Physics/PhysicsScene.h>
  10. #include <AzFramework/Physics/RigidBodyBus.h>
  11. #include <AzFramework/Physics/SimulatedBodies/RigidBody.h>
  12. #include <ROS2/Utilities/ROS2Conversions.h>
  13. #include <ROS2/Utilities/ROS2Names.h>
  14. namespace ROS2Sensors
  15. {
  16. namespace
  17. {
  18. const char* OdometryMsgType = "nav_msgs::msg::Odometry";
  19. }
  20. void ROS2OdometrySensorComponent::Reflect(AZ::ReflectContext* context)
  21. {
  22. if (auto* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  23. {
  24. serialize->Class<ROS2OdometrySensorComponent, SensorBaseType>()->Version(2);
  25. if (auto* editContext = serialize->GetEditContext())
  26. {
  27. editContext->Class<ROS2OdometrySensorComponent>("ROS2 Odometry Sensor", "Odometry sensor component")
  28. ->ClassElement(AZ::Edit::ClassElements::EditorData, "")
  29. ->Attribute(AZ::Edit::Attributes::Category, "ROS2")
  30. ->Attribute(AZ::Edit::Attributes::AppearsInAddComponentMenu, AZ_CRC_CE("Game"))
  31. ->Attribute(AZ::Edit::Attributes::Icon, "Editor/Icons/Components/ROS2OdometrySensor.svg")
  32. ->Attribute(AZ::Edit::Attributes::ViewportIcon, "Editor/Icons/Components/Viewport/ROS2OdometrySensor.svg");
  33. }
  34. }
  35. }
  36. ROS2OdometrySensorComponent::ROS2OdometrySensorComponent()
  37. : m_initialTransform(AZ::Transform::CreateIdentity())
  38. {
  39. ROS2::TopicConfiguration tc;
  40. const AZStd::string type = OdometryMsgType;
  41. tc.m_type = type;
  42. tc.m_topic = "odom";
  43. m_sensorConfiguration.m_frequency = 10;
  44. m_sensorConfiguration.m_publishersConfigurations.insert(AZStd::make_pair(type, tc));
  45. }
  46. void ROS2OdometrySensorComponent::GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required)
  47. {
  48. required.push_back(AZ_CRC_CE("PhysicsDynamicRigidBodyService"));
  49. required.push_back(AZ_CRC_CE("ROS2Frame"));
  50. }
  51. void ROS2OdometrySensorComponent::GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible)
  52. {
  53. incompatible.push_back(AZ_CRC("ArticulationLinkService"));
  54. }
  55. void ROS2OdometrySensorComponent::OnOdometryEvent(AzPhysics::SceneHandle sceneHandle)
  56. {
  57. if (m_bodyHandle == AzPhysics::InvalidSimulatedBodyHandle)
  58. {
  59. AzPhysics::RigidBody* rigidBody = nullptr;
  60. AZ::EntityId entityId = GetEntityId();
  61. Physics::RigidBodyRequestBus::EventResult(rigidBody, entityId, &Physics::RigidBodyRequests::GetRigidBody);
  62. AZ_Assert(rigidBody, "Entity %s does not have rigid body.", entityId.ToString().c_str());
  63. m_bodyHandle = rigidBody->m_bodyHandle;
  64. auto* sceneInterface = AZ::Interface<AzPhysics::SceneInterface>::Get();
  65. AZ_Assert(sceneInterface, "Requested scene interface is missing");
  66. auto* simulatedBodyPtr = sceneInterface->GetSimulatedBodyFromHandle(sceneHandle, m_bodyHandle);
  67. auto* rigidbodyPtr = azrtti_cast<AzPhysics::RigidBody*>(simulatedBodyPtr);
  68. AZ_Assert(rigidbodyPtr, "Requested simulated body is not a rigid body");
  69. m_initialTransform = rigidbodyPtr->GetTransform();
  70. }
  71. auto* sceneInterface = AZ::Interface<AzPhysics::SceneInterface>::Get();
  72. AZ_Assert(sceneInterface, "Requested scene interface is missing");
  73. auto* simulatedBodyPtr = sceneInterface->GetSimulatedBodyFromHandle(sceneHandle, m_bodyHandle);
  74. auto* rigidbodyPtr = azrtti_cast<AzPhysics::RigidBody*>(simulatedBodyPtr);
  75. AZ_Assert(rigidbodyPtr, "Requested simulated body is not a rigid body");
  76. const auto transform = rigidbodyPtr->GetTransform().GetInverse();
  77. const auto localAngular = transform.TransformVector(rigidbodyPtr->GetAngularVelocity());
  78. const auto localLinear = transform.TransformVector(rigidbodyPtr->GetLinearVelocity());
  79. m_odometryMsg.header.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
  80. m_odometryMsg.twist.twist.linear = ROS2::ROS2Conversions::ToROS2Vector3(localLinear);
  81. m_odometryMsg.twist.twist.angular = ROS2::ROS2Conversions::ToROS2Vector3(localAngular);
  82. const auto odometry = m_initialTransform.GetInverse() * rigidbodyPtr->GetTransform();
  83. m_odometryMsg.pose.pose = ROS2::ROS2Conversions::ToROS2Pose(odometry);
  84. m_odometryPublisher->publish(m_odometryMsg);
  85. }
  86. void ROS2OdometrySensorComponent::Activate()
  87. {
  88. ROS2SensorComponentBase::Activate();
  89. // "odom" is globally fixed frame for all robots, no matter the namespace
  90. m_odometryMsg.header.frame_id = ROS2::ROS2Names::GetNamespacedName(GetNamespace(), "odom").c_str();
  91. m_odometryMsg.child_frame_id = GetFrameID().c_str();
  92. auto ros2Node = ROS2::ROS2Interface::Get()->GetNode();
  93. AZ_Assert(m_sensorConfiguration.m_publishersConfigurations.size() == 1, "Invalid configuration of publishers for Odometry sensor");
  94. const auto publisherConfig = m_sensorConfiguration.m_publishersConfigurations[OdometryMsgType];
  95. const auto fullTopic = ROS2::ROS2Names::GetNamespacedName(GetNamespace(), publisherConfig.m_topic);
  96. m_odometryPublisher = ros2Node->create_publisher<nav_msgs::msg::Odometry>(fullTopic.data(), publisherConfig.GetQoS());
  97. StartSensor(
  98. m_sensorConfiguration.m_frequency,
  99. [this]([[maybe_unused]] float odomDeltaTime, AzPhysics::SceneHandle sceneHandle, [[maybe_unused]] float physicsDeltaTime)
  100. {
  101. if (!m_sensorConfiguration.m_publishingEnabled)
  102. {
  103. return;
  104. }
  105. OnOdometryEvent(sceneHandle);
  106. });
  107. }
  108. void ROS2OdometrySensorComponent::Deactivate()
  109. {
  110. StopSensor();
  111. m_odometryPublisher.reset();
  112. ROS2SensorComponentBase::Deactivate();
  113. }
  114. } // namespace ROS2Sensors