ROS2WheelOdometrySensorComponent.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251
  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 "ROS2WheelOdometrySensorComponent.h"
  9. #include <AzCore/Serialization/Json/JsonSerialization.h>
  10. #include <AzCore/Serialization/Json/JsonSerializationResult.h>
  11. #include <AzCore/Serialization/Json/RegistrationContext.h>
  12. #include <ROS2/Utilities/ROS2Conversions.h>
  13. #include <ROS2/Utilities/ROS2Names.h>
  14. #include <ROS2Controllers/Sensors/ROS2OdometryCovariance.h>
  15. #include <ROS2Controllers/VehicleDynamics/VehicleInputControlBus.h>
  16. namespace ROS2Controllers
  17. {
  18. namespace
  19. {
  20. const char* WheelOdometryMsgType = "nav_msgs::msg::Odometry";
  21. }
  22. // Manual conversion between version without a configuration struct and with a configuration struct.
  23. // This is done to maintain backwards compatibility with older versions of the component.
  24. // This function checks if in the prefab there exits a member called "Twist covariance" or "Pose covariance".
  25. // If it does, it will load the values into the new configuration struct.
  26. // If it doesn't, it will treat the loaded json as it would load the new version of the component.
  27. // Checking old members is used instead of checking if there is a member called "Odometry configuration"
  28. // because is default values are used O3DE does not create an empty member and initializes the component with default values.
  29. // Meaning if there does not exist a member called "Odometry configuration" this component could use old values or default ones.
  30. AZ::JsonSerializationResult::Result JsonROS2WheelOdometryComponentConfigSerializer::Load(
  31. void* outputValue, const AZ::Uuid& outputValueTypeId, const rapidjson::Value& inputValue, AZ::JsonDeserializerContext& context)
  32. {
  33. namespace JSR = AZ::JsonSerializationResult;
  34. auto configInstance = reinterpret_cast<ROS2WheelOdometryComponent*>(outputValue);
  35. AZ_Assert(configInstance, "Output value for JsonROS2WheelOdometryComponentConfigSerializer can't be null.");
  36. JSR::ResultCode result(JSR::Tasks::ReadField);
  37. const bool hasOldMembers = inputValue.HasMember("Twist covariance") || inputValue.HasMember("Pose covariance");
  38. if (hasOldMembers)
  39. {
  40. {
  41. JSR::ResultCode componentIdLoadResult = ContinueLoadingFromJsonObjectField(
  42. &configInstance->m_odometryConfiguration.m_poseCovariance,
  43. azrtti_typeid<decltype(configInstance->m_odometryConfiguration.m_poseCovariance)>(),
  44. inputValue,
  45. "Pose covariance",
  46. context);
  47. result.Combine(componentIdLoadResult);
  48. }
  49. {
  50. JSR::ResultCode componentIdLoadResult = ContinueLoadingFromJsonObjectField(
  51. &configInstance->m_odometryConfiguration.m_twistCovariance,
  52. azrtti_typeid<decltype(configInstance->m_odometryConfiguration.m_twistCovariance)>(),
  53. inputValue,
  54. "Twist covariance",
  55. context);
  56. result.Combine(componentIdLoadResult);
  57. }
  58. }
  59. else
  60. {
  61. {
  62. JSR::ResultCode componentIdLoadResult = ContinueLoadingFromJsonObjectField(
  63. &configInstance->m_odometryConfiguration,
  64. azrtti_typeid<decltype(configInstance->m_odometryConfiguration)>(),
  65. inputValue,
  66. "Odometry configuration",
  67. context);
  68. result.Combine(componentIdLoadResult);
  69. }
  70. }
  71. {
  72. JSR::ResultCode componentIdLoadResult = ContinueLoadingFromJsonObjectField(
  73. &configInstance->m_sensorConfiguration,
  74. azrtti_typeid<decltype(configInstance->m_sensorConfiguration)>(),
  75. inputValue,
  76. "Sensor configuration",
  77. context);
  78. result.Combine(componentIdLoadResult);
  79. }
  80. return context.Report(
  81. result,
  82. result.GetProcessing() != JSR::Processing::Halted ? "Successfully loaded ROS2FrameComponent information."
  83. : "Failed to load ROS2FrameComponent information.");
  84. }
  85. AZ_CLASS_ALLOCATOR_IMPL(JsonROS2WheelOdometryComponentConfigSerializer, AZ::SystemAllocator);
  86. void ROS2WheelOdometryComponent::Reflect(AZ::ReflectContext* context)
  87. {
  88. if (auto jsonContext = azrtti_cast<AZ::JsonRegistrationContext*>(context))
  89. {
  90. jsonContext->Serializer<JsonROS2WheelOdometryComponentConfigSerializer>()->HandlesType<ROS2WheelOdometryComponent>();
  91. }
  92. WheelOdometrySensorConfiguration::Reflect(context);
  93. if (auto* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  94. {
  95. serialize->Class<ROS2WheelOdometryComponent, SensorBaseType>()->Version(3)->Field(
  96. "Odometry configuration", &ROS2WheelOdometryComponent::m_odometryConfiguration);
  97. if (auto* editContext = serialize->GetEditContext())
  98. {
  99. editContext->Class<ROS2WheelOdometryComponent>("ROS2 Wheel Odometry Sensor", "Odometry sensor component")
  100. ->ClassElement(AZ::Edit::ClassElements::EditorData, "")
  101. ->Attribute(AZ::Edit::Attributes::Category, "ROS2")
  102. ->Attribute(AZ::Edit::Attributes::AppearsInAddComponentMenu, AZ_CRC_CE("Game"))
  103. ->Attribute(AZ::Edit::Attributes::Icon, "Editor/Icons/Components/ROS2WheelOdometrySensor.svg")
  104. ->Attribute(AZ::Edit::Attributes::ViewportIcon, "Editor/Icons/Components/Viewport/ROS2WheelOdometrySensor.svg")
  105. ->DataElement(
  106. AZ::Edit::UIHandlers::Default,
  107. &ROS2WheelOdometryComponent::m_odometryConfiguration,
  108. "Odometry configuration",
  109. "Odometry sensor configuration")
  110. ->Attribute(AZ::Edit::Attributes::Visibility, AZ::Edit::PropertyVisibility::ShowChildrenOnly);
  111. }
  112. }
  113. }
  114. ROS2WheelOdometryComponent::ROS2WheelOdometryComponent()
  115. {
  116. ROS2::TopicConfiguration tc;
  117. const AZStd::string type = WheelOdometryMsgType;
  118. tc.m_type = type;
  119. tc.m_topic = "odom";
  120. m_sensorConfiguration.m_frequency = 10;
  121. m_sensorConfiguration.m_publishersConfigurations.insert(AZStd::make_pair(type, tc));
  122. }
  123. void ROS2WheelOdometryComponent::GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required)
  124. {
  125. required.push_back(AZ_CRC_CE("ROS2Frame"));
  126. required.push_back(AZ_CRC_CE("SkidSteeringModelService"));
  127. }
  128. void ROS2WheelOdometryComponent::OnOdometryEvent()
  129. {
  130. m_odometryMsg.pose.pose.position = ROS2::ROS2Conversions::ToROS2Point(m_robotPose);
  131. m_odometryMsg.pose.pose.orientation = ROS2::ROS2Conversions::ToROS2Quaternion(m_robotRotation);
  132. m_odometryMsg.pose.covariance = m_odometryConfiguration.m_poseCovariance.GetRosCovariance();
  133. m_odometryPublisher->publish(m_odometryMsg);
  134. }
  135. void ROS2WheelOdometryComponent::OnPhysicsEvent(float physicsDeltaTime)
  136. {
  137. AZStd::pair<AZ::Vector3, AZ::Vector3> vt;
  138. VehicleDynamics::VehicleInputControlRequestBus::EventResult(
  139. vt, GetEntityId(), &VehicleDynamics::VehicleInputControlRequests::GetWheelsOdometry);
  140. m_odometryMsg.header.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
  141. m_odometryMsg.twist.twist.linear = ROS2::ROS2Conversions::ToROS2Vector3(vt.first);
  142. m_odometryMsg.twist.twist.angular = ROS2::ROS2Conversions::ToROS2Vector3(vt.second);
  143. m_odometryMsg.twist.covariance = m_odometryConfiguration.m_twistCovariance.GetRosCovariance();
  144. if (m_sensorConfiguration.m_frequency > 0)
  145. {
  146. const auto updatePos = physicsDeltaTime * vt.first; // in meters
  147. const auto updateRot = physicsDeltaTime * vt.second; // in radians
  148. m_robotPose += m_robotRotation.TransformVector(updatePos);
  149. m_robotRotation *= AZ::Quaternion::CreateFromScaledAxisAngle(updateRot);
  150. }
  151. }
  152. void ROS2WheelOdometryComponent::Activate()
  153. {
  154. ROS2SensorComponentBase::Activate();
  155. m_robotPose = AZ::Vector3{ 0 };
  156. m_robotRotation = AZ::Quaternion{ 0, 0, 0, 1 };
  157. // "odom" is globally fixed frame for all robots, no matter the namespace
  158. m_odometryMsg.header.frame_id = ROS2::ROS2Names::GetNamespacedName(GetNamespace(), "odom").c_str();
  159. m_odometryMsg.child_frame_id = GetFrameID().c_str();
  160. auto ros2Node = ROS2::ROS2Interface::Get()->GetNode();
  161. AZ_Assert(m_sensorConfiguration.m_publishersConfigurations.size() == 1, "Invalid configuration of publishers for Odometry sensor");
  162. const auto& publisherConfig = m_sensorConfiguration.m_publishersConfigurations[WheelOdometryMsgType];
  163. const auto fullTopic = ROS2::ROS2Names::GetNamespacedName(GetNamespace(), publisherConfig.m_topic);
  164. m_odometryPublisher = ros2Node->create_publisher<nav_msgs::msg::Odometry>(fullTopic.data(), publisherConfig.GetQoS());
  165. StartSensor(
  166. m_sensorConfiguration.m_frequency,
  167. [this]([[maybe_unused]] auto&&... args)
  168. {
  169. if (!m_sensorConfiguration.m_publishingEnabled)
  170. {
  171. return;
  172. }
  173. OnOdometryEvent();
  174. },
  175. [this]([[maybe_unused]] AzPhysics::SceneHandle sceneHandle, float physicsDeltaTime)
  176. {
  177. OnPhysicsEvent(physicsDeltaTime);
  178. });
  179. WheelOdometryConfigurationRequestBus::Handler::BusConnect(GetEntityId());
  180. }
  181. void ROS2WheelOdometryComponent::Deactivate()
  182. {
  183. WheelOdometryConfigurationRequestBus::Handler::BusDisconnect(GetEntityId());
  184. StopSensor();
  185. m_odometryPublisher.reset();
  186. ROS2SensorComponentBase::Deactivate();
  187. }
  188. const WheelOdometrySensorConfiguration ROS2WheelOdometryComponent::GetConfiguration()
  189. {
  190. return m_odometryConfiguration;
  191. }
  192. void ROS2WheelOdometryComponent::SetConfiguration(const WheelOdometrySensorConfiguration& configuration)
  193. {
  194. m_odometryConfiguration = configuration;
  195. }
  196. ROS2OdometryCovariance ROS2WheelOdometryComponent::GetPoseCovariance()
  197. {
  198. return m_odometryConfiguration.m_poseCovariance;
  199. }
  200. void ROS2WheelOdometryComponent::SetPoseCovariance(const ROS2OdometryCovariance& covariance)
  201. {
  202. m_odometryConfiguration.m_poseCovariance = covariance;
  203. }
  204. ROS2OdometryCovariance ROS2WheelOdometryComponent::GetTwistCovariance()
  205. {
  206. return m_odometryConfiguration.m_twistCovariance;
  207. }
  208. void ROS2WheelOdometryComponent::SetTwistCovariance(const ROS2OdometryCovariance& covariance)
  209. {
  210. m_odometryConfiguration.m_twistCovariance = covariance;
  211. }
  212. } // namespace ROS2Controllers