ROS2CameraSensorEditorComponent.cpp 8.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209
  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 "ROS2CameraSensorEditorComponent.h"
  9. #include "CameraConstants.h"
  10. #include "CameraUtilities.h"
  11. #include "ROS2CameraSensorComponent.h"
  12. #include <AzCore/Component/TransformBus.h>
  13. #include <ROS2/Frame/ROS2FrameComponent.h>
  14. namespace ROS2
  15. {
  16. ROS2CameraSensorEditorComponent::ROS2CameraSensorEditorComponent()
  17. {
  18. m_sensorConfiguration.m_frequency = 10;
  19. m_sensorConfiguration.m_publishersConfigurations.insert(
  20. MakeTopicConfigurationPair("camera_image_color", CameraConstants::ImageMessageType, CameraConstants::ColorImageConfig));
  21. m_sensorConfiguration.m_publishersConfigurations.insert(
  22. MakeTopicConfigurationPair("camera_image_depth", CameraConstants::ImageMessageType, CameraConstants::DepthImageConfig));
  23. m_sensorConfiguration.m_publishersConfigurations.insert(
  24. MakeTopicConfigurationPair("color_camera_info", CameraConstants::CameraInfoMessageType, CameraConstants::ColorInfoConfig));
  25. m_sensorConfiguration.m_publishersConfigurations.insert(
  26. MakeTopicConfigurationPair("depth_camera_info", CameraConstants::CameraInfoMessageType, CameraConstants::DepthInfoConfig));
  27. }
  28. ROS2CameraSensorEditorComponent::ROS2CameraSensorEditorComponent(
  29. const SensorConfiguration& sensorConfiguration, const CameraSensorConfiguration& cameraConfiguration)
  30. : m_sensorConfiguration(sensorConfiguration)
  31. , m_cameraSensorConfiguration(cameraConfiguration)
  32. {
  33. }
  34. void ROS2CameraSensorEditorComponent::Reflect(AZ::ReflectContext* context)
  35. {
  36. if (auto* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  37. {
  38. serialize->Class<ROS2CameraSensorEditorComponent, AzToolsFramework::Components::EditorComponentBase>()
  39. ->Version(4)
  40. ->Field("CameraSensorConfig", &ROS2CameraSensorEditorComponent::m_cameraSensorConfiguration)
  41. ->Field("SensorConfig", &ROS2CameraSensorEditorComponent::m_sensorConfiguration);
  42. if (AZ::EditContext* editContext = serialize->GetEditContext())
  43. {
  44. editContext->Class<ROS2CameraSensorEditorComponent>("ROS2 Camera Sensor", "[Camera component]")
  45. ->ClassElement(AZ::Edit::ClassElements::EditorData, "")
  46. ->Attribute(AZ::Edit::Attributes::Category, "ROS2")
  47. ->Attribute(AZ::Edit::Attributes::AppearsInAddComponentMenu, AZ_CRC("Game"))
  48. ->DataElement(
  49. AZ::Edit::UIHandlers::Default,
  50. &ROS2CameraSensorEditorComponent::m_sensorConfiguration,
  51. "Sensor configuration",
  52. "Sensor configuration")
  53. ->DataElement(
  54. AZ::Edit::UIHandlers::Default,
  55. &ROS2CameraSensorEditorComponent::m_cameraSensorConfiguration,
  56. "Camera configuration",
  57. "Camera configuration.");
  58. }
  59. }
  60. }
  61. void ROS2CameraSensorEditorComponent::Activate()
  62. {
  63. AzFramework::EntityDebugDisplayEventBus::Handler::BusConnect(this->GetEntityId());
  64. AzToolsFramework::Components::EditorComponentBase::Activate();
  65. ROS2::CameraCalibrationRequestBus::Handler::BusConnect(GetEntityId());
  66. }
  67. void ROS2CameraSensorEditorComponent::Deactivate()
  68. {
  69. AzToolsFramework::Components::EditorComponentBase::Deactivate();
  70. AzFramework::EntityDebugDisplayEventBus::Handler::BusDisconnect();
  71. ROS2::CameraCalibrationRequestBus::Handler::BusDisconnect(GetEntityId());
  72. }
  73. void ROS2CameraSensorEditorComponent::GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required)
  74. {
  75. required.push_back(AZ_CRC("ROS2Frame"));
  76. }
  77. void ROS2CameraSensorEditorComponent::GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible)
  78. {
  79. incompatible.push_back(AZ_CRC_CE("ROS2CameraSensor"));
  80. }
  81. void ROS2CameraSensorEditorComponent::GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided)
  82. {
  83. provided.push_back(AZ_CRC_CE("ROS2CameraSensor"));
  84. }
  85. void ROS2CameraSensorEditorComponent::BuildGameEntity(AZ::Entity* gameEntity)
  86. {
  87. gameEntity->CreateComponent<ROS2::ROS2CameraSensorComponent>(m_sensorConfiguration, m_cameraSensorConfiguration);
  88. }
  89. AZ::Matrix3x3 ROS2CameraSensorEditorComponent::GetCameraMatrix() const
  90. {
  91. return CameraUtils::MakeCameraIntrinsics(
  92. m_cameraSensorConfiguration.m_width,
  93. m_cameraSensorConfiguration.m_height,
  94. m_cameraSensorConfiguration.m_verticalFieldOfViewDeg);
  95. };
  96. int ROS2CameraSensorEditorComponent::GetWidth() const
  97. {
  98. return m_cameraSensorConfiguration.m_width;
  99. };
  100. int ROS2CameraSensorEditorComponent::GetHeight() const
  101. {
  102. return m_cameraSensorConfiguration.m_height;
  103. };
  104. float ROS2CameraSensorEditorComponent::GetVerticalFOV() const
  105. {
  106. return m_cameraSensorConfiguration.m_verticalFieldOfViewDeg;
  107. };
  108. void ROS2CameraSensorEditorComponent::DisplayEntityViewport(
  109. [[maybe_unused]] const AzFramework::ViewportInfo& viewportInfo, AzFramework::DebugDisplayRequests& debugDisplay)
  110. {
  111. if (!m_sensorConfiguration.m_visualize)
  112. {
  113. return;
  114. }
  115. const AZ::u32 stateBefore = debugDisplay.GetState();
  116. AZ::Transform transform = GetEntity()->GetTransform()->GetWorldTM();
  117. const float distance = m_cameraSensorConfiguration.m_farClipDistance * 0.1f;
  118. const float tangent = static_cast<float>(tan(0.5f * AZ::DegToRad(m_cameraSensorConfiguration.m_verticalFieldOfViewDeg)));
  119. float height = distance * tangent;
  120. float width = height * m_cameraSensorConfiguration.m_width / m_cameraSensorConfiguration.m_height;
  121. AZ::Vector3 farPoints[4];
  122. farPoints[0] = AZ::Vector3(width, height, distance);
  123. farPoints[1] = AZ::Vector3(-width, height, distance);
  124. farPoints[2] = AZ::Vector3(-width, -height, distance);
  125. farPoints[3] = AZ::Vector3(width, -height, distance);
  126. AZ::Vector3 nearPoints[4];
  127. nearPoints[0] = farPoints[0].GetNormalizedSafe() * m_cameraSensorConfiguration.m_nearClipDistance;
  128. nearPoints[1] = farPoints[1].GetNormalizedSafe() * m_cameraSensorConfiguration.m_nearClipDistance;
  129. nearPoints[2] = farPoints[2].GetNormalizedSafe() * m_cameraSensorConfiguration.m_nearClipDistance;
  130. nearPoints[3] = farPoints[3].GetNormalizedSafe() * m_cameraSensorConfiguration.m_nearClipDistance;
  131. // dimension of drawing
  132. const float arrowRise = 0.11f;
  133. const float arrowSize = 0.05f;
  134. const AZ::Vector3 pt0(0, 0, 0);
  135. const auto ptz = AZ::Vector3::CreateAxisZ(0.2f);
  136. const auto pty = AZ::Vector3::CreateAxisY(0.2f);
  137. const auto ptx = AZ::Vector3::CreateAxisX(0.2f);
  138. debugDisplay.PushMatrix(transform);
  139. debugDisplay.SetColor(AZ::Color(0.f, 1.f, 1.f, 1.f));
  140. debugDisplay.DrawLine(nearPoints[0], farPoints[0]);
  141. debugDisplay.DrawLine(nearPoints[1], farPoints[1]);
  142. debugDisplay.DrawLine(nearPoints[2], farPoints[2]);
  143. debugDisplay.DrawLine(nearPoints[3], farPoints[3]);
  144. debugDisplay.DrawPolyLine(nearPoints, AZ_ARRAY_SIZE(nearPoints));
  145. debugDisplay.DrawPolyLine(farPoints, AZ_ARRAY_SIZE(farPoints));
  146. // up-arrow drawing
  147. const AZ::Vector3 pa1(-arrowSize * height, -arrowRise * width, 1.f);
  148. const AZ::Vector3 pa2(arrowSize * height, -arrowRise * width, 1.f);
  149. const AZ::Vector3 pa3(0, (-arrowRise - arrowSize) * width, 1.f);
  150. debugDisplay.SetColor(AZ::Color(0.f, 0.6f, 1.f, 1.f));
  151. debugDisplay.SetLineWidth(1);
  152. debugDisplay.DrawLine(pa1, pa2);
  153. debugDisplay.DrawLine(pa2, pa3);
  154. debugDisplay.DrawLine(pa3, pa1);
  155. // coordinate system drawing
  156. debugDisplay.SetColor(AZ::Color(1.f, 0.f, 0.f, 1.f));
  157. debugDisplay.SetLineWidth(2);
  158. debugDisplay.DrawLine(ptx, pt0);
  159. debugDisplay.SetColor(AZ::Color(0.f, 1.f, 0.f, 1.f));
  160. debugDisplay.SetLineWidth(2);
  161. debugDisplay.DrawLine(pty, pt0);
  162. debugDisplay.SetColor(AZ::Color(0.f, 0.f, 1.f, 1.f));
  163. debugDisplay.SetLineWidth(2);
  164. debugDisplay.DrawLine(ptz, pt0);
  165. debugDisplay.PopMatrix();
  166. debugDisplay.SetState(stateBefore);
  167. }
  168. AZStd::pair<AZStd::string, TopicConfiguration> ROS2CameraSensorEditorComponent::MakeTopicConfigurationPair(
  169. const AZStd::string& topic, const AZStd::string& messageType, const AZStd::string& configName) const
  170. {
  171. TopicConfiguration config;
  172. config.m_topic = topic;
  173. config.m_type = messageType;
  174. return AZStd::make_pair(configName, config);
  175. }
  176. } // namespace ROS2