Skip to content

File continental_srr520_decoder_wrapper.hpp

File List > continental > continental_srr520_decoder_wrapper.hpp

Go to the documentation of this file

// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include "nebula_ros/common/parameter_descriptors.hpp"
#include "nebula_ros/common/watchdog_timer.hpp"

#include <nebula_common/continental/continental_srr520.hpp>
#include <nebula_common/nebula_common.hpp>
#include <nebula_common/util/expected.hpp>
#include <nebula_decoders/nebula_decoders_continental/decoders/continental_srr520_decoder.hpp>
#include <nebula_hw_interfaces/nebula_hw_interfaces_continental/continental_srr520_hw_interface.hpp>
#include <rclcpp/rclcpp.hpp>

#include <continental_msgs/msg/continental_srr520_detection.hpp>
#include <continental_msgs/msg/continental_srr520_detection_list.hpp>
#include <continental_msgs/msg/continental_srr520_object.hpp>
#include <continental_msgs/msg/continental_srr520_object_list.hpp>
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
#include <nebula_msgs/msg/nebula_packet.hpp>
#include <nebula_msgs/msg/nebula_packets.hpp>
#include <radar_msgs/msg/radar_scan.hpp>
#include <radar_msgs/msg/radar_tracks.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <memory>
#include <mutex>
#include <unordered_set>
#include <vector>

namespace nebula
{
namespace ros
{
class ContinentalSRR520DecoderWrapper
{
public:
  ContinentalSRR520DecoderWrapper(
    rclcpp::Node * const parent_node,
    std::shared_ptr<const drivers::continental_srr520::ContinentalSRR520SensorConfiguration> &
      config,
    std::shared_ptr<drivers::continental_srr520::ContinentalSRR520HwInterface> hw_interface_ptr);

  void ProcessPacket(std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg);

  void OnConfigChange(
    const std::shared_ptr<
      const nebula::drivers::continental_srr520::ContinentalSRR520SensorConfiguration> &
      new_config_ptr);

  rcl_interfaces::msg::SetParametersResult OnParameterChange(
    const std::vector<rclcpp::Parameter> & p);

  nebula::Status Status();

  void NearDetectionListCallback(
    std::unique_ptr<continental_msgs::msg::ContinentalSrr520DetectionList> msg);

  void HRRDetectionListCallback(
    std::unique_ptr<continental_msgs::msg::ContinentalSrr520DetectionList> msg);

  void ObjectListCallback(std::unique_ptr<continental_msgs::msg::ContinentalSrr520ObjectList> msg);

  void StatusCallback(std::unique_ptr<diagnostic_msgs::msg::DiagnosticArray> msg);

  void SyncFollowUpCallback(builtin_interfaces::msg::Time stamp);

  void PacketsCallback(std::unique_ptr<nebula_msgs::msg::NebulaPackets> msg);

private:
  nebula::Status InitializeDriver(
    const std::shared_ptr<
      const nebula::drivers::continental_srr520::ContinentalSRR520SensorConfiguration> & config);

  pcl::PointCloud<nebula::drivers::continental_srr520::PointSRR520Detection>::Ptr
  ConvertToPointcloud(const continental_msgs::msg::ContinentalSrr520DetectionList & msg);

  pcl::PointCloud<nebula::drivers::continental_srr520::PointSRR520Object>::Ptr ConvertToPointcloud(
    const continental_msgs::msg::ContinentalSrr520ObjectList & msg);

  radar_msgs::msg::RadarScan ConvertToRadarScan(
    const continental_msgs::msg::ContinentalSrr520DetectionList & msg);

  radar_msgs::msg::RadarTracks ConvertToRadarTracks(
    const continental_msgs::msg::ContinentalSrr520ObjectList & msg);

  visualization_msgs::msg::MarkerArray ConvertToMarkers(
    const continental_msgs::msg::ContinentalSrr520ObjectList & msg);

  const rclcpp::Node * const parent_node_;
  nebula::Status status_;
  rclcpp::Logger logger_;

  std::shared_ptr<const nebula::drivers::continental_srr520::ContinentalSRR520SensorConfiguration>
    sensor_cfg_{};

  std::shared_ptr<drivers::continental_srr520::ContinentalSRR520Decoder> driver_ptr_{};
  std::shared_ptr<drivers::continental_srr520::ContinentalSRR520HwInterface> hw_interface_ptr_{};
  std::mutex mtx_driver_ptr_;

  rclcpp::Publisher<nebula_msgs::msg::NebulaPackets>::SharedPtr packets_pub_{};

  rclcpp::Publisher<continental_msgs::msg::ContinentalSrr520DetectionList>::SharedPtr
    near_detection_list_pub_{};
  rclcpp::Publisher<continental_msgs::msg::ContinentalSrr520DetectionList>::SharedPtr
    hrr_detection_list_pub_{};
  rclcpp::Publisher<continental_msgs::msg::ContinentalSrr520ObjectList>::SharedPtr
    object_list_pub_{};
  rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr status_pub_{};
  rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr near_detection_pointcloud_pub_{};
  rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr hrr_detection_pointcloud_pub_{};
  rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr object_pointcloud_pub_{};
  rclcpp::Publisher<radar_msgs::msg::RadarScan>::SharedPtr near_scan_raw_pub_{};
  rclcpp::Publisher<radar_msgs::msg::RadarScan>::SharedPtr hrr_scan_raw_pub_{};
  rclcpp::Publisher<radar_msgs::msg::RadarTracks>::SharedPtr objects_raw_pub_{};
  rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr objects_markers_pub_{};

  std::unordered_set<int> previous_ids_{};

  std::shared_ptr<WatchdogTimer> watchdog_;
};
}  // namespace ros
}  // namespace nebula