CameraSensor.cpp 9.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243
  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 "CameraSensor.h"
  9. #include <AzCore/Math/MatrixUtils.h>
  10. #include <Atom/RPI.Public/Base.h>
  11. #include <Atom/RPI.Public/Pass/Specific/RenderToTexturePass.h>
  12. #include <Atom/RPI.Public/RPISystemInterface.h>
  13. #include <Atom/RPI.Public/RenderPipeline.h>
  14. #include <Atom/RPI.Public/Scene.h>
  15. #include <AzFramework/Components/TransformComponent.h>
  16. #include <AzFramework/Scene/SceneSystemInterface.h>
  17. #include <Atom/RPI.Public/FeatureProcessorFactory.h>
  18. #include <Atom/RPI.Public/Pass/PassSystemInterface.h>
  19. #include <PostProcess/PostProcessFeatureProcessor.h>
  20. #include <Atom/RPI.Public/Pass/PassFactory.h>
  21. namespace ROS2
  22. {
  23. namespace Internal
  24. {
  25. /// @FormatMappings - contains the mapping from RHI to ROS image encodings. List of supported
  26. /// ROS image encodings lives in `sensor_msgs/image_encodings.hpp`
  27. /// We are not including `image_encodings.hpp` since it uses exceptions.
  28. AZStd::unordered_map<AZ::RHI::Format, const char*> FormatMappings{
  29. { AZ::RHI::Format::R8G8B8A8_UNORM, "rgba8" },
  30. { AZ::RHI::Format::R16G16B16A16_UNORM, "rgba16" },
  31. { AZ::RHI::Format::R32G32B32A32_FLOAT, "32FC4" }, // Unsuported by RVIZ2
  32. { AZ::RHI::Format::R8_UNORM, "mono8" },
  33. { AZ::RHI::Format::R16_UNORM, "mono16" },
  34. { AZ::RHI::Format::R32_FLOAT, "32FC1" },
  35. };
  36. /// @BitDepth - contains the mapping from RHI to size used in `step` size computation.
  37. /// It is some equivalent to `bitDepth()` function from `sensor_msgs/image_encodings.hpp`
  38. AZStd::unordered_map<AZ::RHI::Format, int> BitDepth{
  39. { AZ::RHI::Format::R8G8B8A8_UNORM, 4 * sizeof(uint8_t) },
  40. { AZ::RHI::Format::R16G16B16A16_UNORM, 4 * sizeof(uint16_t) },
  41. { AZ::RHI::Format::R32G32B32A32_FLOAT, 4 * sizeof(float) }, // Unsuported by RVIZ2
  42. { AZ::RHI::Format::R8_UNORM, sizeof(uint8_t) },
  43. { AZ::RHI::Format::R16_UNORM, sizeof(uint16_t) },
  44. { AZ::RHI::Format::R32_FLOAT, sizeof(float) },
  45. };
  46. } // namespace Internal
  47. CameraSensorDescription::CameraSensorDescription(const AZStd::string& cameraName, float verticalFov, int width, int height)
  48. : m_verticalFieldOfViewDeg(verticalFov)
  49. , m_width(width)
  50. , m_height(height)
  51. , m_cameraName(cameraName)
  52. , m_aspectRatio(static_cast<float>(width) / static_cast<float>(height))
  53. , m_viewToClipMatrix(MakeViewToClipMatrix())
  54. , m_cameraIntrinsics(MakeCameraIntrinsics())
  55. {
  56. ValidateParameters();
  57. }
  58. AZ::Matrix4x4 CameraSensorDescription::MakeViewToClipMatrix() const
  59. {
  60. const float nearDist = 0.1f, farDist = 100.0f;
  61. AZ::Matrix4x4 localViewToClipMatrix;
  62. AZ::MakePerspectiveFovMatrixRH(
  63. localViewToClipMatrix, AZ::DegToRad(m_verticalFieldOfViewDeg), m_aspectRatio, nearDist, farDist, true);
  64. return localViewToClipMatrix;
  65. }
  66. void CameraSensorDescription::ValidateParameters() const
  67. {
  68. AZ_Assert(
  69. m_verticalFieldOfViewDeg > 0.0f && m_verticalFieldOfViewDeg < 180.0f,
  70. "Vertical fov should be in range 0.0 < FoV < 180.0 degrees");
  71. AZ_Assert(!m_cameraName.empty(), "Camera name cannot be empty");
  72. }
  73. AZStd::array<double, 9> CameraSensorDescription::MakeCameraIntrinsics() const
  74. {
  75. /* Intrinsic camera matrix of the camera image is being created here
  76. It is based on other parameters available in the structure - they must be initialized before this function is called
  77. Matrix is row-major and has the following form:
  78. [fx 0 cx]
  79. [ 0 fy cy]
  80. [ 0 0 1]
  81. Projects 3D points in the camera coordinate frame to 2D pixel
  82. coordinates using the focal lengths (fx, fy) and principal point
  83. (cx, cy).
  84. */
  85. const auto w = static_cast<double>(m_width);
  86. const auto h = static_cast<double>(m_height);
  87. const double verticalFieldOfView = AZ::DegToRad(m_verticalFieldOfViewDeg);
  88. const double horizontalFoV = 2.0 * AZStd::atan(AZStd::tan(verticalFieldOfView / 2.0) * m_aspectRatio);
  89. const double focalLengthX = w / (2.0 * AZStd::tan(horizontalFoV / 2.0));
  90. const double focalLengthY = h / (2.0 * AZStd::tan(verticalFieldOfView / 2.0));
  91. return { focalLengthX, 0.0, w / 2.0, 0.0, focalLengthY, h / 2.0, 0.0, 0.0, 1.0 };
  92. }
  93. CameraSensor::CameraSensor(const CameraSensorDescription& cameraSensorDescription)
  94. : m_cameraSensorDescription(cameraSensorDescription)
  95. {
  96. }
  97. void CameraSensor::SetupPasses()
  98. {
  99. AZ_TracePrintf("CameraSensor", "Initializing pipeline for %s\n", m_cameraSensorDescription.m_cameraName.c_str());
  100. const AZ::Name viewName = AZ::Name("MainCamera");
  101. m_view = AZ::RPI::View::CreateView(viewName, AZ::RPI::View::UsageCamera);
  102. m_view->SetViewToClipMatrix(m_cameraSensorDescription.m_viewToClipMatrix);
  103. m_scene = AZ::RPI::RPISystemInterface::Get()->GetSceneByName(AZ::Name("Main"));
  104. const AZStd::string pipelineName = m_cameraSensorDescription.m_cameraName + "Pipeline" + GetPipelineTypeName();
  105. AZ::RPI::RenderPipelineDescriptor pipelineDesc;
  106. pipelineDesc.m_mainViewTagName = "MainCamera";
  107. pipelineDesc.m_name = pipelineName;
  108. pipelineDesc.m_rootPassTemplate = GetPipelineTemplateName();
  109. pipelineDesc.m_renderSettings.m_multisampleState = AZ::RPI::RPISystemInterface::Get()->GetApplicationMultisampleState();
  110. m_pipeline = AZ::RPI::RenderPipeline::CreateRenderPipeline(pipelineDesc);
  111. m_pipeline->RemoveFromRenderTick();
  112. if (auto renderToTexturePass = azrtti_cast<AZ::RPI::RenderToTexturePass*>(m_pipeline->GetRootPass().get()))
  113. {
  114. renderToTexturePass->ResizeOutput(m_cameraSensorDescription.m_width, m_cameraSensorDescription.m_height);
  115. }
  116. m_scene->AddRenderPipeline(m_pipeline);
  117. m_passHierarchy.push_back(pipelineName);
  118. m_passHierarchy.push_back("CopyToSwapChain");
  119. m_pipeline->SetDefaultView(m_view);
  120. const AZ::RPI::ViewPtr targetView = m_scene->GetDefaultRenderPipeline()->GetDefaultView();
  121. if (auto* fp = m_scene->GetFeatureProcessor<AZ::Render::PostProcessFeatureProcessor>())
  122. {
  123. fp->SetViewAlias(m_view, targetView);
  124. }
  125. }
  126. CameraSensor::~CameraSensor()
  127. {
  128. if (m_scene)
  129. {
  130. if (auto* fp = m_scene->GetFeatureProcessor<AZ::Render::PostProcessFeatureProcessor>())
  131. {
  132. fp->RemoveViewAlias(m_view);
  133. }
  134. m_scene->RemoveRenderPipeline(m_pipeline->GetId());
  135. m_scene = nullptr;
  136. }
  137. m_passHierarchy.clear();
  138. m_pipeline.reset();
  139. m_view.reset();
  140. }
  141. void CameraSensor::RequestFrame(
  142. const AZ::Transform& cameraPose, AZStd::function<void(const AZ::RPI::AttachmentReadback::ReadbackResult& result)> callback)
  143. {
  144. const AZ::Transform inverse = (cameraPose * AtomToRos).GetInverse();
  145. m_view->SetWorldToViewMatrix(AZ::Matrix4x4::CreateFromQuaternionAndTranslation(inverse.GetRotation(), inverse.GetTranslation()));
  146. AZ::Render::FrameCaptureId captureId = AZ::Render::InvalidFrameCaptureId;
  147. m_pipeline->AddToRenderTickOnce();
  148. AZ::Render::FrameCaptureRequestBus::BroadcastResult(
  149. captureId,
  150. &AZ::Render::FrameCaptureRequestBus::Events::CapturePassAttachmentWithCallback,
  151. m_passHierarchy,
  152. AZStd::string("Output"),
  153. callback,
  154. AZ::RPI::PassAttachmentReadbackOption::Output);
  155. }
  156. const CameraSensorDescription& CameraSensor::GetCameraSensorDescription() const
  157. {
  158. return m_cameraSensorDescription;
  159. }
  160. void CameraSensor::RequestMessagePublication(
  161. std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>> publisher,
  162. const AZ::Transform& cameraPose,
  163. const std_msgs::msg::Header& header)
  164. {
  165. RequestFrame(
  166. cameraPose,
  167. [header, publisher](const AZ::RPI::AttachmentReadback::ReadbackResult& result)
  168. {
  169. const AZ::RHI::ImageDescriptor& descriptor = result.m_imageDescriptor;
  170. const auto format = descriptor.m_format;
  171. AZ_Assert(Internal::FormatMappings.contains(format), "Unknown format in result %u", static_cast<uint32_t>(format));
  172. sensor_msgs::msg::Image message;
  173. message.encoding = Internal::FormatMappings.at(format);
  174. message.width = descriptor.m_size.m_width;
  175. message.height = descriptor.m_size.m_height;
  176. message.step = message.width * Internal::BitDepth.at(format);
  177. message.data = std::vector<uint8_t>(result.m_dataBuffer->data(), result.m_dataBuffer->data() + result.m_dataBuffer->size());
  178. message.header = header;
  179. publisher->publish(message);
  180. });
  181. }
  182. CameraDepthSensor::CameraDepthSensor(const CameraSensorDescription& cameraSensorDescription)
  183. : CameraSensor(cameraSensorDescription)
  184. {
  185. SetupPasses();
  186. }
  187. AZStd::string CameraDepthSensor::GetPipelineTemplateName() const
  188. {
  189. return "PipelineRenderToTextureROSDepth";
  190. };
  191. AZStd::string CameraDepthSensor::GetPipelineTypeName() const
  192. {
  193. return "Depth";
  194. };
  195. CameraColorSensor::CameraColorSensor(const CameraSensorDescription& cameraSensorDescription)
  196. : CameraSensor(cameraSensorDescription)
  197. {
  198. SetupPasses();
  199. }
  200. AZStd::string CameraColorSensor::GetPipelineTemplateName() const
  201. {
  202. return "PipelineRenderToTextureROSColor";
  203. };
  204. AZStd::string CameraColorSensor::GetPipelineTypeName() const
  205. {
  206. return "Color";
  207. };
  208. } // namespace ROS2