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