Class WLSFilter
Defined in File wls_filter.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class WLSFilter : public rclcpp::Node
Public Types
-
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo, sensor_msgs::msg::Image> syncPolicy
Public Functions
-
explicit WLSFilter(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
-
void onInit()
-
rcl_interfaces::msg::SetParametersResult parameterCB(const std::vector<rclcpp::Parameter> ¶ms)
Public Members
-
OnSetParametersCallbackHandle::SharedPtr paramCBHandle
-
message_filters::Subscriber<sensor_msgs::msg::Image> disparityImgSub
-
message_filters::Subscriber<sensor_msgs::msg::Image> leftImgSub
-
message_filters::Subscriber<sensor_msgs::msg::CameraInfo> disparityInfoSub
-
std::unique_ptr<message_filters::Synchronizer<syncPolicy>> sync
-
cv::Ptr<cv::ximgproc::DisparityWLSFilter> filter
-
image_transport::CameraPublisher depthPub
-
double maxDisparity
-
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo, sensor_msgs::msg::Image> syncPolicy