2
0

ROS2WheelOdometry.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140
  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 "ROS2WheelOdometry.h"
  9. #include "Odometry/ROS2OdometryCovariance.h"
  10. #include "VehicleModelComponent.h"
  11. #include <ROS2/Utilities/ROS2Conversions.h>
  12. #include <ROS2/Utilities/ROS2Names.h>
  13. namespace ROS2
  14. {
  15. namespace
  16. {
  17. const char* WheelOdometryMsgType = "nav_msgs::msg::Odometry";
  18. }
  19. void ROS2WheelOdometryComponent::Reflect(AZ::ReflectContext* context)
  20. {
  21. ROS2OdometryCovariance::Reflect(context);
  22. if (auto* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  23. {
  24. serialize->Class<ROS2WheelOdometryComponent, SensorBaseType>()
  25. ->Version(2)
  26. ->Field("Twist covariance", &ROS2WheelOdometryComponent::m_twistCovariance)
  27. ->Field("Pose covariance", &ROS2WheelOdometryComponent::m_poseCovariance);
  28. if (auto* editContext = serialize->GetEditContext())
  29. {
  30. editContext->Class<ROS2WheelOdometryComponent>("ROS2 Wheel Odometry Sensor", "Odometry sensor component")
  31. ->ClassElement(AZ::Edit::ClassElements::EditorData, "")
  32. ->Attribute(AZ::Edit::Attributes::Category, "ROS2")
  33. ->Attribute(AZ::Edit::Attributes::AppearsInAddComponentMenu, AZ_CRC_CE("Game"))
  34. ->Attribute(AZ::Edit::Attributes::Icon, "Editor/Icons/Components/ROS2WheelOdometrySensor.svg")
  35. ->Attribute(AZ::Edit::Attributes::ViewportIcon, "Editor/Icons/Components/Viewport/ROS2WheelOdometrySensor.svg")
  36. ->DataElement(
  37. AZ::Edit::UIHandlers::Default,
  38. &ROS2WheelOdometryComponent::m_twistCovariance,
  39. "Twist covariance",
  40. "Set ROS twist covariance")
  41. ->DataElement(
  42. AZ::Edit::UIHandlers::Default,
  43. &ROS2WheelOdometryComponent::m_poseCovariance,
  44. "Pose covariance",
  45. "Set ROS pose covariance");
  46. }
  47. }
  48. }
  49. ROS2WheelOdometryComponent::ROS2WheelOdometryComponent()
  50. {
  51. TopicConfiguration tc;
  52. const AZStd::string type = WheelOdometryMsgType;
  53. tc.m_type = type;
  54. tc.m_topic = "odom";
  55. m_sensorConfiguration.m_frequency = 10;
  56. m_sensorConfiguration.m_publishersConfigurations.insert(AZStd::make_pair(type, tc));
  57. }
  58. void ROS2WheelOdometryComponent::GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required)
  59. {
  60. required.push_back(AZ_CRC_CE("ROS2Frame"));
  61. required.push_back(AZ_CRC_CE("SkidSteeringModelService"));
  62. }
  63. void ROS2WheelOdometryComponent::OnOdometryEvent()
  64. {
  65. m_odometryMsg.pose.pose.position = ROS2Conversions::ToROS2Point(m_robotPose);
  66. m_odometryMsg.pose.pose.orientation = ROS2Conversions::ToROS2Quaternion(m_robotRotation);
  67. m_odometryMsg.pose.covariance = m_poseCovariance.GetRosCovariance();
  68. m_odometryPublisher->publish(m_odometryMsg);
  69. }
  70. void ROS2WheelOdometryComponent::OnPhysicsEvent(float physicsDeltaTime)
  71. {
  72. AZStd::pair<AZ::Vector3, AZ::Vector3> vt;
  73. VehicleDynamics::VehicleInputControlRequestBus::EventResult(
  74. vt, GetEntityId(), &VehicleDynamics::VehicleInputControlRequests::GetWheelsOdometry);
  75. m_odometryMsg.header.stamp = ROS2Interface::Get()->GetROSTimestamp();
  76. m_odometryMsg.twist.twist.linear = ROS2Conversions::ToROS2Vector3(vt.first);
  77. m_odometryMsg.twist.twist.angular = ROS2Conversions::ToROS2Vector3(vt.second);
  78. m_odometryMsg.twist.covariance = m_twistCovariance.GetRosCovariance();
  79. if (m_sensorConfiguration.m_frequency > 0)
  80. {
  81. const auto updatePos = physicsDeltaTime * vt.first; // in meters
  82. const auto updateRot = physicsDeltaTime * vt.second; // in radians
  83. m_robotPose += m_robotRotation.TransformVector(updatePos);
  84. m_robotRotation *= AZ::Quaternion::CreateFromScaledAxisAngle(updateRot);
  85. }
  86. }
  87. void ROS2WheelOdometryComponent::Activate()
  88. {
  89. ROS2SensorComponentBase::Activate();
  90. m_robotPose = AZ::Vector3{ 0 };
  91. m_robotRotation = AZ::Quaternion{ 0, 0, 0, 1 };
  92. // "odom" is globally fixed frame for all robots, no matter the namespace
  93. m_odometryMsg.header.frame_id = ROS2Names::GetNamespacedName(GetNamespace(), "odom").c_str();
  94. m_odometryMsg.child_frame_id = GetFrameID().c_str();
  95. auto ros2Node = ROS2Interface::Get()->GetNode();
  96. AZ_Assert(m_sensorConfiguration.m_publishersConfigurations.size() == 1, "Invalid configuration of publishers for Odometry sensor");
  97. const auto& publisherConfig = m_sensorConfiguration.m_publishersConfigurations[WheelOdometryMsgType];
  98. const auto fullTopic = ROS2Names::GetNamespacedName(GetNamespace(), publisherConfig.m_topic);
  99. m_odometryPublisher = ros2Node->create_publisher<nav_msgs::msg::Odometry>(fullTopic.data(), publisherConfig.GetQoS());
  100. StartSensor(
  101. m_sensorConfiguration.m_frequency,
  102. [this]([[maybe_unused]] auto&&... args)
  103. {
  104. if (!m_sensorConfiguration.m_publishingEnabled)
  105. {
  106. return;
  107. }
  108. OnOdometryEvent();
  109. },
  110. [this]([[maybe_unused]] AzPhysics::SceneHandle sceneHandle, float physicsDeltaTime)
  111. {
  112. OnPhysicsEvent(physicsDeltaTime);
  113. });
  114. }
  115. void ROS2WheelOdometryComponent::Deactivate()
  116. {
  117. StopSensor();
  118. m_odometryPublisher.reset();
  119. ROS2SensorComponentBase::Deactivate();
  120. }
  121. } // namespace ROS2