36 #include <boost/thread.hpp> 58 void imageCb(
const sensor_msgs::ImageConstPtr& raw_msg);
70 pub_ =
it_->advertise(
"image", 1, connect_cb, connect_cb);
97 ROS_ERROR(
"cv_bridge exception: %s", e.what());
107 std::vector<std::vector<cv::Point> >cnt;
108 cv::Mat1b m(raw_msg->width, raw_msg->height);
110 if (raw_msg->encoding == enc::TYPE_8UC1){
113 double minVal, maxVal;
114 cv::minMaxIdx(cv_ptr->image, &minVal, &maxVal, 0, 0, cv_ptr->image != 0.);
115 double ra = maxVal - minVal;
117 cv_ptr->image.convertTo(m, CV_8U, 255./ra, -minVal*255./ra);
120 cv::findContours(m, cnt, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
128 std::vector<std::vector<cv::Point> >::iterator it = cnt.begin();
129 for(std::vector<std::vector<cv::Point> >::iterator i=cnt.begin();i!=cnt.end();++i){
130 it = (*it).size() < (*i).size() ? i : it;
132 cv::Rect r = cv::boundingRect(cnt[std::distance(cnt.begin(), it)]);
135 out_msg.
header = raw_msg->header;
136 out_msg.
encoding = raw_msg->encoding;
137 out_msg.
image = cv_ptr->image(r);
uint32_t getNumSubscribers() const
ros::NodeHandle & getNodeHandle() const
#define NODELET_ERROR_THROTTLE(rate,...)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::NodeHandle & getPrivateNodeHandle() const
image_transport::Publisher pub_
sensor_msgs::ImagePtr toImageMsg() const
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void publish(const sensor_msgs::Image &message) const
static int numChannels(const std::string &encoding)
void imageCb(const sensor_msgs::ImageConstPtr &raw_msg)
boost::shared_ptr< image_transport::ImageTransport > it_
boost::mutex connect_mutex_
image_transport::Subscriber sub_raw_