ROS2CameraSensorEditorComponent.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304
  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 "CameraUtilities.h"
  10. #include "ROS2CameraSensorComponent.h"
  11. #include <AzCore/Component/TransformBus.h>
  12. namespace ROS2Sensors
  13. {
  14. ROS2CameraSensorEditorComponent::ROS2CameraSensorEditorComponent()
  15. {
  16. m_sensorConfiguration.m_frequency = 10;
  17. m_sensorConfiguration.m_publishersConfigurations.insert(
  18. MakeTopicConfigurationPair("camera_image_color", CameraConstants::ImageMessageType, CameraConstants::ColorImageConfig));
  19. m_sensorConfiguration.m_publishersConfigurations.insert(
  20. MakeTopicConfigurationPair("camera_image_depth", CameraConstants::ImageMessageType, CameraConstants::DepthImageConfig));
  21. m_sensorConfiguration.m_publishersConfigurations.insert(
  22. MakeTopicConfigurationPair("color_camera_info", CameraConstants::CameraInfoMessageType, CameraConstants::ColorInfoConfig));
  23. m_sensorConfiguration.m_publishersConfigurations.insert(
  24. MakeTopicConfigurationPair("depth_camera_info", CameraConstants::CameraInfoMessageType, CameraConstants::DepthInfoConfig));
  25. }
  26. ROS2CameraSensorEditorComponent::ROS2CameraSensorEditorComponent(
  27. const ROS2::SensorConfiguration& sensorConfiguration, const CameraSensorConfiguration& cameraConfiguration)
  28. : m_sensorConfiguration(sensorConfiguration)
  29. , m_cameraConfiguration(cameraConfiguration)
  30. {
  31. }
  32. void ROS2CameraSensorEditorComponent::Reflect(AZ::ReflectContext* context)
  33. {
  34. if (auto* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  35. {
  36. serialize->Class<ROS2CameraSensorEditorComponent, AzToolsFramework::Components::EditorComponentBase>()
  37. ->Version(4)
  38. ->Field("CameraSensorConfig", &ROS2CameraSensorEditorComponent::m_cameraConfiguration)
  39. ->Field("SensorConfig", &ROS2CameraSensorEditorComponent::m_sensorConfiguration);
  40. if (AZ::EditContext* editContext = serialize->GetEditContext())
  41. {
  42. editContext->Class<ROS2CameraSensorEditorComponent>("ROS2 Camera Sensor", "[Camera component]")
  43. ->ClassElement(AZ::Edit::ClassElements::EditorData, "")
  44. ->Attribute(AZ::Edit::Attributes::Category, "ROS2")
  45. ->Attribute(AZ::Edit::Attributes::AppearsInAddComponentMenu, AZ_CRC("Game"))
  46. ->Attribute(AZ::Edit::Attributes::Icon, "Editor/Icons/Components/ROS2CameraSensor.svg")
  47. ->Attribute(AZ::Edit::Attributes::ViewportIcon, "Editor/Icons/Components/Viewport/ROS2CameraSensor.svg")
  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_cameraConfiguration,
  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. CameraConfigurationRequestBus::Handler::BusConnect(GetEntityId());
  66. }
  67. void ROS2CameraSensorEditorComponent::Deactivate()
  68. {
  69. CameraConfigurationRequestBus::Handler::BusDisconnect(GetEntityId());
  70. AzToolsFramework::Components::EditorComponentBase::Deactivate();
  71. AzFramework::EntityDebugDisplayEventBus::Handler::BusDisconnect();
  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<ROS2CameraSensorComponent>(m_sensorConfiguration, m_cameraConfiguration);
  88. }
  89. void ROS2CameraSensorEditorComponent::SetConfiguration(const CameraSensorConfiguration& configuration)
  90. {
  91. m_cameraConfiguration = configuration;
  92. }
  93. const CameraSensorConfiguration ROS2CameraSensorEditorComponent::GetConfiguration()
  94. {
  95. return m_cameraConfiguration;
  96. }
  97. AZ::Matrix3x3 ROS2CameraSensorEditorComponent::GetCameraMatrix()
  98. {
  99. return CameraUtils::MakeCameraIntrinsics(
  100. m_cameraConfiguration.m_width, m_cameraConfiguration.m_height, m_cameraConfiguration.m_verticalFieldOfViewDeg);
  101. }
  102. float ROS2CameraSensorEditorComponent::GetVerticalFOV()
  103. {
  104. return m_cameraConfiguration.m_verticalFieldOfViewDeg;
  105. }
  106. void ROS2CameraSensorEditorComponent::SetVerticalFOV(float value)
  107. {
  108. if (value < CameraSensorConfiguration::m_minVerticalFieldOfViewDeg ||
  109. value > CameraSensorConfiguration::m_maxVerticalFieldOfViewDeg)
  110. {
  111. AZ_Warning(
  112. "ROS2CameraSensorEditorComponent",
  113. false,
  114. "Vertical field of view value %f is out of bounds [%f, %f].",
  115. value,
  116. CameraSensorConfiguration::m_minVerticalFieldOfViewDeg,
  117. CameraSensorConfiguration::m_maxVerticalFieldOfViewDeg);
  118. return;
  119. }
  120. m_cameraConfiguration.m_verticalFieldOfViewDeg = value;
  121. }
  122. int ROS2CameraSensorEditorComponent::GetWidth()
  123. {
  124. return m_cameraConfiguration.m_width;
  125. }
  126. void ROS2CameraSensorEditorComponent::SetWidth(int value)
  127. {
  128. if (value < CameraSensorConfiguration::m_minWidth)
  129. {
  130. AZ_Warning(
  131. "ROS2CameraSensorEditorComponent",
  132. false,
  133. "Width value %d is less than the minimum allowed width %d.",
  134. value,
  135. CameraSensorConfiguration::m_minWidth);
  136. return;
  137. }
  138. m_cameraConfiguration.m_width = value;
  139. }
  140. int ROS2CameraSensorEditorComponent::GetHeight()
  141. {
  142. return m_cameraConfiguration.m_height;
  143. }
  144. void ROS2CameraSensorEditorComponent::SetHeight(int value)
  145. {
  146. if (value < CameraSensorConfiguration::m_minHeight)
  147. {
  148. AZ_Warning(
  149. "ROS2CameraSensorEditorComponent",
  150. false,
  151. "Height value %d is less than the minimum allowed height %d.",
  152. value,
  153. CameraSensorConfiguration::m_minHeight);
  154. return;
  155. }
  156. m_cameraConfiguration.m_height = value;
  157. }
  158. bool ROS2CameraSensorEditorComponent::IsColorCamera()
  159. {
  160. return m_cameraConfiguration.m_colorCamera;
  161. }
  162. void ROS2CameraSensorEditorComponent::SetColorCamera(bool value)
  163. {
  164. m_cameraConfiguration.m_colorCamera = value;
  165. }
  166. bool ROS2CameraSensorEditorComponent::IsDepthCamera()
  167. {
  168. return m_cameraConfiguration.m_depthCamera;
  169. }
  170. void ROS2CameraSensorEditorComponent::SetDepthCamera(bool value)
  171. {
  172. m_cameraConfiguration.m_depthCamera = value;
  173. }
  174. float ROS2CameraSensorEditorComponent::GetNearClipDistance()
  175. {
  176. return m_cameraConfiguration.m_nearClipDistance;
  177. }
  178. void ROS2CameraSensorEditorComponent::SetNearClipDistance(float value)
  179. {
  180. m_cameraConfiguration.m_nearClipDistance = value;
  181. }
  182. float ROS2CameraSensorEditorComponent::GetFarClipDistance()
  183. {
  184. return m_cameraConfiguration.m_farClipDistance;
  185. }
  186. void ROS2CameraSensorEditorComponent::SetFarClipDistance(float value)
  187. {
  188. m_cameraConfiguration.m_farClipDistance = value;
  189. }
  190. void ROS2CameraSensorEditorComponent::DisplayEntityViewport(
  191. [[maybe_unused]] const AzFramework::ViewportInfo& viewportInfo, AzFramework::DebugDisplayRequests& debugDisplay)
  192. {
  193. if (!m_sensorConfiguration.m_visualize)
  194. {
  195. return;
  196. }
  197. const AZ::u32 stateBefore = debugDisplay.GetState();
  198. AZ::Transform transform = GetEntity()->GetTransform()->GetWorldTM();
  199. const float distance = m_cameraConfiguration.m_farClipDistance * 0.1f;
  200. const float tangent = static_cast<float>(tan(0.5f * AZ::DegToRad(m_cameraConfiguration.m_verticalFieldOfViewDeg)));
  201. float height = distance * tangent;
  202. float width = height * m_cameraConfiguration.m_width / m_cameraConfiguration.m_height;
  203. AZ::Vector3 farPoints[4];
  204. farPoints[0] = AZ::Vector3(width, height, distance);
  205. farPoints[1] = AZ::Vector3(-width, height, distance);
  206. farPoints[2] = AZ::Vector3(-width, -height, distance);
  207. farPoints[3] = AZ::Vector3(width, -height, distance);
  208. AZ::Vector3 nearPoints[4];
  209. nearPoints[0] = farPoints[0].GetNormalizedSafe() * m_cameraConfiguration.m_nearClipDistance;
  210. nearPoints[1] = farPoints[1].GetNormalizedSafe() * m_cameraConfiguration.m_nearClipDistance;
  211. nearPoints[2] = farPoints[2].GetNormalizedSafe() * m_cameraConfiguration.m_nearClipDistance;
  212. nearPoints[3] = farPoints[3].GetNormalizedSafe() * m_cameraConfiguration.m_nearClipDistance;
  213. // dimension of drawing
  214. const float arrowRise = 0.11f;
  215. const float arrowSize = 0.05f;
  216. const AZ::Vector3 pt0(0, 0, 0);
  217. const auto ptz = AZ::Vector3::CreateAxisZ(0.2f);
  218. const auto pty = AZ::Vector3::CreateAxisY(0.2f);
  219. const auto ptx = AZ::Vector3::CreateAxisX(0.2f);
  220. debugDisplay.PushMatrix(transform);
  221. debugDisplay.SetColor(AZ::Color(0.f, 1.f, 1.f, 1.f));
  222. debugDisplay.DrawLine(nearPoints[0], farPoints[0]);
  223. debugDisplay.DrawLine(nearPoints[1], farPoints[1]);
  224. debugDisplay.DrawLine(nearPoints[2], farPoints[2]);
  225. debugDisplay.DrawLine(nearPoints[3], farPoints[3]);
  226. debugDisplay.DrawPolyLine(nearPoints, AZ_ARRAY_SIZE(nearPoints));
  227. debugDisplay.DrawPolyLine(farPoints, AZ_ARRAY_SIZE(farPoints));
  228. // up-arrow drawing
  229. const AZ::Vector3 pa1(-arrowSize * height, -arrowRise * width, 1.f);
  230. const AZ::Vector3 pa2(arrowSize * height, -arrowRise * width, 1.f);
  231. const AZ::Vector3 pa3(0, (-arrowRise - arrowSize) * width, 1.f);
  232. debugDisplay.SetColor(AZ::Color(0.f, 0.6f, 1.f, 1.f));
  233. debugDisplay.SetLineWidth(1);
  234. debugDisplay.DrawLine(pa1, pa2);
  235. debugDisplay.DrawLine(pa2, pa3);
  236. debugDisplay.DrawLine(pa3, pa1);
  237. // coordinate system drawing
  238. debugDisplay.SetColor(AZ::Color(1.f, 0.f, 0.f, 1.f));
  239. debugDisplay.SetLineWidth(2);
  240. debugDisplay.DrawLine(ptx, pt0);
  241. debugDisplay.SetColor(AZ::Color(0.f, 1.f, 0.f, 1.f));
  242. debugDisplay.SetLineWidth(2);
  243. debugDisplay.DrawLine(pty, pt0);
  244. debugDisplay.SetColor(AZ::Color(0.f, 0.f, 1.f, 1.f));
  245. debugDisplay.SetLineWidth(2);
  246. debugDisplay.DrawLine(ptz, pt0);
  247. debugDisplay.PopMatrix();
  248. debugDisplay.SetState(stateBefore);
  249. }
  250. AZStd::pair<AZStd::string, ROS2::TopicConfiguration> ROS2CameraSensorEditorComponent::MakeTopicConfigurationPair(
  251. const AZStd::string& topic, const AZStd::string& messageType, const AZStd::string& configName) const
  252. {
  253. ROS2::TopicConfiguration config;
  254. config.m_topic = topic;
  255. config.m_type = messageType;
  256. return AZStd::make_pair(configName, config);
  257. }
  258. } // namespace ROS2Sensors