node.hpp 2.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970
  1. // Copyright 2021 TIER IV, Inc.
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. #ifndef LIDAR_CENTERPOINT__NODE_HPP_
  15. #define LIDAR_CENTERPOINT__NODE_HPP_
  16. #include "lidar_centerpoint/postprocess/non_maximum_suppression.hpp"
  17. #include <lidar_centerpoint/centerpoint_trt.hpp>
  18. #include <lidar_centerpoint/detection_class_remapper.hpp>
  19. #include <rclcpp/rclcpp.hpp>
  20. #include <tier4_autoware_utils/ros/debug_publisher.hpp>
  21. #include <tier4_autoware_utils/system/stop_watch.hpp>
  22. #include <autoware_auto_perception_msgs/msg/detected_object_kinematics.hpp>
  23. #include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
  24. #include <autoware_auto_perception_msgs/msg/object_classification.hpp>
  25. #include <autoware_auto_perception_msgs/msg/shape.hpp>
  26. #include <sensor_msgs/msg/point_cloud2.hpp>
  27. #include <memory>
  28. #include <string>
  29. #include <vector>
  30. namespace centerpoint
  31. {
  32. class LidarCenterPointNode : public rclcpp::Node
  33. {
  34. public:
  35. explicit LidarCenterPointNode(const rclcpp::NodeOptions & node_options);
  36. private:
  37. void pointCloudCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_pointcloud_msg);
  38. tf2_ros::Buffer tf_buffer_;
  39. tf2_ros::TransformListener tf_listener_{tf_buffer_};
  40. rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr pointcloud_sub_;
  41. rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr objects_pub_;
  42. float score_threshold_{0.0};
  43. std::vector<std::string> class_names_;
  44. bool has_twist_{false};
  45. NonMaximumSuppression iou_bev_nms_;
  46. DetectionClassRemapper detection_class_remapper_;
  47. std::unique_ptr<CenterPointTRT> detector_ptr_{nullptr};
  48. // debugger
  49. std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_{
  50. nullptr};
  51. std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_ptr_{nullptr};
  52. };
  53. } // namespace centerpoint
  54. #endif // LIDAR_CENTERPOINT__NODE_HPP_