ROS2LidarSensorComponent.h 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990
  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. #pragma once
  9. #include "LidarCore.h"
  10. #include "LidarRaycaster.h"
  11. #include <Atom/RPI.Public/AuxGeom/AuxGeomDraw.h>
  12. #include <AzCore/Serialization/SerializeContext.h>
  13. #include <ROS2/Sensor/Events/TickBasedSource.h>
  14. #include <ROS2/Sensor/ROS2SensorComponentBase.h>
  15. #include <ROS2Sensors/Lidar/LidarConfigurationRequestBus.h>
  16. #include <ROS2Sensors/Lidar/LidarSensorConfiguration.h>
  17. #include <rclcpp/publisher.hpp>
  18. #include <sensor_msgs/msg/point_cloud2.hpp>
  19. #include <vision_msgs/msg/label_info.hpp>
  20. namespace ROS2Sensors
  21. {
  22. //! Lidar sensor Component.
  23. //! Lidars (Light Detection and Ranging) emit laser light and measure it after reflection.
  24. //! Lidar Component allows customization of lidar type and behavior and encapsulates both simulation
  25. //! and data publishing. It requires ROS2FrameComponent.
  26. class ROS2LidarSensorComponent
  27. : public ROS2::ROS2SensorComponentBase<ROS2::TickBasedSource>
  28. , protected LidarConfigurationRequestBus::Handler
  29. {
  30. public:
  31. using SensorBaseType = ROS2::ROS2SensorComponentBase<ROS2::TickBasedSource>;
  32. AZ_COMPONENT(ROS2LidarSensorComponent, ROS2LidarSensorComponentTypeId, SensorBaseType);
  33. ROS2LidarSensorComponent();
  34. ROS2LidarSensorComponent(const ROS2::SensorConfiguration& sensorConfiguration, const LidarSensorConfiguration& lidarConfiguration);
  35. ~ROS2LidarSensorComponent() = default;
  36. static void Reflect(AZ::ReflectContext* context);
  37. static void GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required);
  38. //////////////////////////////////////////////////////////////////////////
  39. // Component overrides
  40. void Activate() override;
  41. void Deactivate() override;
  42. //////////////////////////////////////////////////////////////////////////
  43. private:
  44. //////////////////////////////////////////////////////////////////////////
  45. // LidarConfigurationRequestBus::Handler overrides
  46. const LidarSensorConfiguration GetConfiguration() override;
  47. void SetConfiguration(const LidarSensorConfiguration& configuration) override;
  48. AZStd::string GetModelName() override;
  49. void SetModelName(const AZStd::string& name) override;
  50. bool IsSegmentationEnabled() override;
  51. void SetSegmentationEnabled(bool enabled) override;
  52. bool IsAddPointsAtMaxEnabled() override;
  53. void SetAddPointsAtMaxEnabled(bool addPoints) override;
  54. bool Is2D() override;
  55. float GetMinHAngle() override;
  56. void SetMinHAngle(float angle) override;
  57. float GetMaxHAngle() override;
  58. void SetMaxHAngle(float angle) override;
  59. float GetMinVAngle() override;
  60. void SetMinVAngle(float angle) override;
  61. float GetMaxVAngle() override;
  62. void SetMaxVAngle(float angle) override;
  63. unsigned int GetLayers() override;
  64. void SetLayers(unsigned int layers) override;
  65. unsigned int GetNumberOfIncrements() override;
  66. void SetNumberOfIncrements(unsigned int increments) override;
  67. float GetMinRange() override;
  68. void SetMinRange(float range) override;
  69. float GetMaxRange() override;
  70. void SetMaxRange(float range) override;
  71. const LidarTemplate::NoiseParameters& GetNoiseParameters() override;
  72. void SetNoiseParameters(const LidarTemplate::NoiseParameters& params) override;
  73. //////////////////////////////////////////////////////////////////////////
  74. void FrequencyTick();
  75. void PublishRaycastResults(const RaycastResults& results);
  76. bool m_canRaycasterPublish = false;
  77. std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::PointCloud2>> m_pointCloudPublisher;
  78. std::shared_ptr<rclcpp::Publisher<vision_msgs::msg::LabelInfo>> m_segmentationClassesPublisher;
  79. LidarCore m_lidarCore;
  80. LidarId m_lidarRaycasterId;
  81. };
  82. } // namespace ROS2Sensors