37 #include <boost/thread.hpp>
39 #include <opencv2/imgproc/imgproc.hpp>
59 void depthCb(
const sensor_msgs::ImageConstPtr& raw_msg);
75 pub_depth_ =
it_->advertise(
"image", 1, connect_cb, connect_cb);
102 ROS_ERROR(
"cv_bridge exception: %s", e.what());
114 cv::minMaxIdx(cv_ptr->image, &minVal, 0, 0, 0, cv_ptr->image != 0);
121 cv::threshold(cv_ptr->image, cv_ptr->image, minVal +
distance_, 0, CV_THRESH_TOZERO_INV);
128 cv_ptr->image.convertTo(cv_ptr->image, CV_32F);
129 cv::threshold(cv_ptr->image, cv_ptr->image, minVal +
distance_, 1, CV_THRESH_TOZERO_INV);
131 cv_ptr->image.convertTo(cv_ptr->image, imtype);