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);
#define NODELET_ERROR_THROTTLE(rate,...)
image_transport::Publisher pub_depth_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< image_transport::ImageTransport > it_
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const sensor_msgs::Image &message) const
PLUGINLIB_EXPORT_CLASS(depth_image_proc::CropForemostNodelet, nodelet::Nodelet)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
boost::mutex connect_mutex_
ros::NodeHandle & getNodeHandle() const
int getCvType(const std::string &encoding)
static int numChannels(const std::string &encoding)
bool getParam(const std::string &key, std::string &s) const
image_transport::Subscriber sub_raw_
void depthCb(const sensor_msgs::ImageConstPtr &raw_msg)