39 #include <rclcpp/rclcpp.hpp>
40 #include <tf2_ros/buffer.h>
45 #include <image_transport/image_transport.hpp>
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);
69 rclcpp::Node::SharedPtr node_;
70 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
71 std::unique_ptr<image_transport::ImageTransport> input_depth_transport_;
72 std::unique_ptr<image_transport::ImageTransport> model_depth_transport_;
73 std::unique_ptr<image_transport::ImageTransport> filtered_depth_transport_;
74 std::unique_ptr<image_transport::ImageTransport> filtered_label_transport_;
76 image_transport::CameraSubscriber sub_depth_image_;
77 image_transport::CameraPublisher pub_model_depth_image_;
78 image_transport::CameraPublisher pub_filtered_depth_image_;
79 image_transport::CameraPublisher pub_filtered_label_image_;
82 rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
84 std::string filtered_cloud_topic_;
86 std::string sensor_type_;
87 std::string image_topic_;
88 std::size_t queue_size_;
89 double near_clipping_plane_distance_;
90 double far_clipping_plane_distance_;
91 double shadow_threshold_;
92 double padding_scale_;
93 double padding_offset_;
94 double max_update_rate_;
95 unsigned int skip_vertical_pixels_;
96 unsigned int skip_horizontal_pixels_;
98 unsigned int image_callback_count_;
99 double average_callback_dt_;
100 unsigned int good_tf_;
101 unsigned int failed_tf_;
103 std::unique_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> > mesh_filter_;
104 std::unique_ptr<LazyFreeSpaceUpdater> free_space_updater_;
106 std::vector<float> x_cache_, y_cache_;
107 double inv_fx_, inv_fy_, K0_, K2_, K4_, K5_;
108 std::vector<unsigned int> filtered_labels_;
109 rclcpp::Time last_depth_callback_start_;
void forgetShape(ShapeHandle handle) override
DepthImageOctomapUpdater()
bool initialize(const rclcpp::Node::SharedPtr &node) override
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) override
~DepthImageOctomapUpdater() override
bool setParams(const std::string &name_space) override
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
Base class for classes which update the occupancy map.