ROS2Lidar2DSensorComponent.h 3.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182
  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/LidarRegistrarBus.h>
  17. #include <ROS2Sensors/Lidar/LidarSystemBus.h>
  18. #include <rclcpp/publisher.hpp>
  19. #include <sensor_msgs/msg/laser_scan.hpp>
  20. namespace ROS2Sensors
  21. {
  22. //! Lidar 2D 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 ROS2Lidar2DSensorComponent
  27. : public ROS2::ROS2SensorComponentBase<ROS2::TickBasedSource>
  28. , protected LidarConfigurationRequestBus::Handler
  29. {
  30. public:
  31. using SensorBaseType = ROS2::ROS2SensorComponentBase<ROS2::TickBasedSource>;
  32. AZ_COMPONENT(ROS2Lidar2DSensorComponent, ROS2Lidar2DSensorComponentTypeId, SensorBaseType);
  33. ROS2Lidar2DSensorComponent();
  34. ROS2Lidar2DSensorComponent(
  35. const ROS2::SensorConfiguration& sensorConfiguration, const LidarSensorConfiguration& lidarConfiguration);
  36. ~ROS2Lidar2DSensorComponent() = default;
  37. static void GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required);
  38. static void Reflect(AZ::ReflectContext* context);
  39. //////////////////////////////////////////////////////////////////////////
  40. // Component overrides
  41. void Activate() override;
  42. void Deactivate() override;
  43. //////////////////////////////////////////////////////////////////////////
  44. private:
  45. //////////////////////////////////////////////////////////////////////////
  46. // LidarConfigurationRequestBus::Handler overrides
  47. const LidarSensorConfiguration GetConfiguration() override;
  48. void SetConfiguration(const LidarSensorConfiguration& configuration) override;
  49. AZStd::string GetModelName() override;
  50. void SetModelName(const AZStd::string& name) override;
  51. bool IsSegmentationEnabled() override;
  52. void SetSegmentationEnabled(bool enabled) override;
  53. bool IsAddPointsAtMaxEnabled() override;
  54. void SetAddPointsAtMaxEnabled(bool addPoints) override;
  55. bool Is2D() override;
  56. float GetMinHAngle() override;
  57. void SetMinHAngle(float angle) override;
  58. float GetMaxHAngle() override;
  59. void SetMaxHAngle(float angle) override;
  60. unsigned int GetNumberOfIncrements() override;
  61. void SetNumberOfIncrements(unsigned int increments) override;
  62. float GetMinRange() override;
  63. void SetMinRange(float range) override;
  64. float GetMaxRange() override;
  65. void SetMaxRange(float range) override;
  66. const LidarTemplate::NoiseParameters& GetNoiseParameters() override;
  67. void SetNoiseParameters(const LidarTemplate::NoiseParameters& params) override;
  68. //////////////////////////////////////////////////////////////////////////
  69. void FrequencyTick();
  70. void PublishRaycastResults(const RaycastResults& results);
  71. std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::LaserScan>> m_laserScanPublisher;
  72. LidarCore m_lidarCore;
  73. };
  74. } // namespace ROS2Sensors