63 bool setParams(
const std::string& name_space)
override;
64 bool initialize(
const rclcpp::Node::SharedPtr& node)
override;
65 void start()
override;
71 void depthImageCallback(
const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
72 const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg);
75 rclcpp::Node::SharedPtr node_;
76 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
77 std::unique_ptr<image_transport::ImageTransport> input_depth_transport_;
78 std::unique_ptr<image_transport::ImageTransport> model_depth_transport_;
79 std::unique_ptr<image_transport::ImageTransport> filtered_depth_transport_;
80 std::unique_ptr<image_transport::ImageTransport> filtered_label_transport_;
82 image_transport::CameraSubscriber sub_depth_image_;
83 image_transport::CameraPublisher pub_model_depth_image_;
84 image_transport::CameraPublisher pub_filtered_depth_image_;
85 image_transport::CameraPublisher pub_filtered_label_image_;
88 rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
90 std::string filtered_cloud_topic_;
92 std::string sensor_type_;
93 std::string image_topic_;
94 std::size_t queue_size_;
95 double near_clipping_plane_distance_;
96 double far_clipping_plane_distance_;
97 double shadow_threshold_;
98 double padding_scale_;
99 double padding_offset_;
100 double max_update_rate_;
101 unsigned int skip_vertical_pixels_;
102 unsigned int skip_horizontal_pixels_;
104 unsigned int image_callback_count_;
105 double average_callback_dt_;
106 unsigned int good_tf_;
107 unsigned int failed_tf_;
109 std::unique_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> > mesh_filter_;
110 std::unique_ptr<LazyFreeSpaceUpdater> free_space_updater_;
112 std::vector<double> x_cache_, y_cache_;
113 double inv_fx_, inv_fy_, K0_, K2_, K4_, K5_;
114 std::vector<unsigned int> filtered_labels_;
115 rclcpp::Time last_depth_callback_start_;
116 rclcpp::Logger logger_;