ROS2CameraSensorEditorComponent.cpp 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211
  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. ->Attribute(AZ::Edit::Attributes::Icon, "Editor/Icons/Components/ROS2CameraSensor.svg")
  49. ->Attribute(AZ::Edit::Attributes::ViewportIcon, "Editor/Icons/Components/Viewport/ROS2CameraSensor.svg")
  50. ->DataElement(
  51. AZ::Edit::UIHandlers::Default,
  52. &ROS2CameraSensorEditorComponent::m_sensorConfiguration,
  53. "Sensor configuration",
  54. "Sensor configuration")
  55. ->DataElement(
  56. AZ::Edit::UIHandlers::Default,
  57. &ROS2CameraSensorEditorComponent::m_cameraSensorConfiguration,
  58. "Camera configuration",
  59. "Camera configuration.");
  60. }
  61. }
  62. }
  63. void ROS2CameraSensorEditorComponent::Activate()
  64. {
  65. AzFramework::EntityDebugDisplayEventBus::Handler::BusConnect(this->GetEntityId());
  66. AzToolsFramework::Components::EditorComponentBase::Activate();
  67. ROS2::CameraCalibrationRequestBus::Handler::BusConnect(GetEntityId());
  68. }
  69. void ROS2CameraSensorEditorComponent::Deactivate()
  70. {
  71. AzToolsFramework::Components::EditorComponentBase::Deactivate();
  72. AzFramework::EntityDebugDisplayEventBus::Handler::BusDisconnect();
  73. ROS2::CameraCalibrationRequestBus::Handler::BusDisconnect(GetEntityId());
  74. }
  75. void ROS2CameraSensorEditorComponent::GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required)
  76. {
  77. required.push_back(AZ_CRC("ROS2Frame"));
  78. }
  79. void ROS2CameraSensorEditorComponent::GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible)
  80. {
  81. incompatible.push_back(AZ_CRC_CE("ROS2CameraSensor"));
  82. }
  83. void ROS2CameraSensorEditorComponent::GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided)
  84. {
  85. provided.push_back(AZ_CRC_CE("ROS2CameraSensor"));
  86. }
  87. void ROS2CameraSensorEditorComponent::BuildGameEntity(AZ::Entity* gameEntity)
  88. {
  89. gameEntity->CreateComponent<ROS2::ROS2CameraSensorComponent>(m_sensorConfiguration, m_cameraSensorConfiguration);
  90. }
  91. AZ::Matrix3x3 ROS2CameraSensorEditorComponent::GetCameraMatrix() const
  92. {
  93. return CameraUtils::MakeCameraIntrinsics(
  94. m_cameraSensorConfiguration.m_width,
  95. m_cameraSensorConfiguration.m_height,
  96. m_cameraSensorConfiguration.m_verticalFieldOfViewDeg);
  97. };
  98. int ROS2CameraSensorEditorComponent::GetWidth() const
  99. {
  100. return m_cameraSensorConfiguration.m_width;
  101. };
  102. int ROS2CameraSensorEditorComponent::GetHeight() const
  103. {
  104. return m_cameraSensorConfiguration.m_height;
  105. };
  106. float ROS2CameraSensorEditorComponent::GetVerticalFOV() const
  107. {
  108. return m_cameraSensorConfiguration.m_verticalFieldOfViewDeg;
  109. };
  110. void ROS2CameraSensorEditorComponent::DisplayEntityViewport(
  111. [[maybe_unused]] const AzFramework::ViewportInfo& viewportInfo, AzFramework::DebugDisplayRequests& debugDisplay)
  112. {
  113. if (!m_sensorConfiguration.m_visualize)
  114. {
  115. return;
  116. }
  117. const AZ::u32 stateBefore = debugDisplay.GetState();
  118. AZ::Transform transform = GetEntity()->GetTransform()->GetWorldTM();
  119. const float distance = m_cameraSensorConfiguration.m_farClipDistance * 0.1f;
  120. const float tangent = static_cast<float>(tan(0.5f * AZ::DegToRad(m_cameraSensorConfiguration.m_verticalFieldOfViewDeg)));
  121. float height = distance * tangent;
  122. float width = height * m_cameraSensorConfiguration.m_width / m_cameraSensorConfiguration.m_height;
  123. AZ::Vector3 farPoints[4];
  124. farPoints[0] = AZ::Vector3(width, height, distance);
  125. farPoints[1] = AZ::Vector3(-width, height, distance);
  126. farPoints[2] = AZ::Vector3(-width, -height, distance);
  127. farPoints[3] = AZ::Vector3(width, -height, distance);
  128. AZ::Vector3 nearPoints[4];
  129. nearPoints[0] = farPoints[0].GetNormalizedSafe() * m_cameraSensorConfiguration.m_nearClipDistance;
  130. nearPoints[1] = farPoints[1].GetNormalizedSafe() * m_cameraSensorConfiguration.m_nearClipDistance;
  131. nearPoints[2] = farPoints[2].GetNormalizedSafe() * m_cameraSensorConfiguration.m_nearClipDistance;
  132. nearPoints[3] = farPoints[3].GetNormalizedSafe() * m_cameraSensorConfiguration.m_nearClipDistance;
  133. // dimension of drawing
  134. const float arrowRise = 0.11f;
  135. const float arrowSize = 0.05f;
  136. const AZ::Vector3 pt0(0, 0, 0);
  137. const auto ptz = AZ::Vector3::CreateAxisZ(0.2f);
  138. const auto pty = AZ::Vector3::CreateAxisY(0.2f);
  139. const auto ptx = AZ::Vector3::CreateAxisX(0.2f);
  140. debugDisplay.PushMatrix(transform);
  141. debugDisplay.SetColor(AZ::Color(0.f, 1.f, 1.f, 1.f));
  142. debugDisplay.DrawLine(nearPoints[0], farPoints[0]);
  143. debugDisplay.DrawLine(nearPoints[1], farPoints[1]);
  144. debugDisplay.DrawLine(nearPoints[2], farPoints[2]);
  145. debugDisplay.DrawLine(nearPoints[3], farPoints[3]);
  146. debugDisplay.DrawPolyLine(nearPoints, AZ_ARRAY_SIZE(nearPoints));
  147. debugDisplay.DrawPolyLine(farPoints, AZ_ARRAY_SIZE(farPoints));
  148. // up-arrow drawing
  149. const AZ::Vector3 pa1(-arrowSize * height, -arrowRise * width, 1.f);
  150. const AZ::Vector3 pa2(arrowSize * height, -arrowRise * width, 1.f);
  151. const AZ::Vector3 pa3(0, (-arrowRise - arrowSize) * width, 1.f);
  152. debugDisplay.SetColor(AZ::Color(0.f, 0.6f, 1.f, 1.f));
  153. debugDisplay.SetLineWidth(1);
  154. debugDisplay.DrawLine(pa1, pa2);
  155. debugDisplay.DrawLine(pa2, pa3);
  156. debugDisplay.DrawLine(pa3, pa1);
  157. // coordinate system drawing
  158. debugDisplay.SetColor(AZ::Color(1.f, 0.f, 0.f, 1.f));
  159. debugDisplay.SetLineWidth(2);
  160. debugDisplay.DrawLine(ptx, pt0);
  161. debugDisplay.SetColor(AZ::Color(0.f, 1.f, 0.f, 1.f));
  162. debugDisplay.SetLineWidth(2);
  163. debugDisplay.DrawLine(pty, pt0);
  164. debugDisplay.SetColor(AZ::Color(0.f, 0.f, 1.f, 1.f));
  165. debugDisplay.SetLineWidth(2);
  166. debugDisplay.DrawLine(ptz, pt0);
  167. debugDisplay.PopMatrix();
  168. debugDisplay.SetState(stateBefore);
  169. }
  170. AZStd::pair<AZStd::string, TopicConfiguration> ROS2CameraSensorEditorComponent::MakeTopicConfigurationPair(
  171. const AZStd::string& topic, const AZStd::string& messageType, const AZStd::string& configName) const
  172. {
  173. TopicConfiguration config;
  174. config.m_topic = topic;
  175. config.m_type = messageType;
  176. return AZStd::make_pair(configName, config);
  177. }
  178. } // namespace ROS2