3 #include <opencv2/core/core.hpp>
4 #include <opencv2/highgui/highgui.hpp>
5 #include <opencv2/imgproc/imgproc.hpp>
7 #include <cv_bridge/cv_bridge.h>
9 #include <image_transport/image_transport.h>
11 #include <sensor_msgs/image_encodings.h>
15 namespace enc = sensor_msgs::image_encodings;
20 image_transport::ImageTransport it_;
21 image_transport::Subscriber image_sub_;
28 ros::NodeHandle nh_local(
"~");
39 void imageCb(
const sensor_msgs::ImageConstPtr& cam_msg)
41 cv_bridge::CvImagePtr cv_ptr;
44 cv_ptr = cv_bridge::toCvCopy(cam_msg, enc::BGR8);
46 catch (cv_bridge::Exception& e)
48 ROS_ERROR(
"cv_bridge exception: %s", e.what());
56 Mat input = cv_ptr->image;
59 Mat grayscaleMat(input.size(), CV_8UC1);
61 cvtColor(input, grayscaleMat, CV_BGR2GRAY);
62 threshold(grayscaleMat, grayscaleMat, 170, 255, THRESH_BINARY);
64 imshow(
"drawing1", grayscaleMat);
70 int main(
int argc,
char** argv)
72 ros::init(argc, argv,
"threshold_imshow_node");
76 cout <<
"estou aqui" << endl;
void imageCb(const sensor_msgs::ImageConstPtr &cam_msg)
int main(int argc, char **argv)