Go to the documentation of this file.00001
00002
00003
00004
00005 #include <ros/ros.h>
00006 #include <image_transport/image_transport.h>
00007 #include <cv_bridge/cv_bridge.h>
00008 #include <sensor_msgs/image_encodings.h>
00009 #include <opencv2/imgproc/imgproc.hpp>
00010 #include <opencv2/highgui/highgui.hpp>
00011
00012 namespace enc = sensor_msgs::image_encodings;
00013
00014 static const char WINDOW_IM[] = "Image window";
00015 static const char WINDOW_SOB[] = "Sobel window";
00016 static const char WINDOW_LAP[] = "Laplacian window";
00017 static const char WINDOW_CAN[] = "Canny window";
00018
00019 class ImageEdge
00020 {
00021 ros::NodeHandle nh_;
00022 image_transport::ImageTransport it_;
00023 image_transport::Subscriber image_sub_;
00024 image_transport::Publisher image_pub_;
00025
00026 public:
00027 ImageEdge()
00028 : it_(nh_)
00029 {
00030 image_pub_ = it_.advertise("image_edge", 1);
00031 image_sub_ = it_.subscribe("image", 1, &ImageEdge::imageCb, this);
00032
00033 cv::namedWindow(WINDOW_IM);
00034 cv::namedWindow(WINDOW_SOB);
00035 cv::namedWindow(WINDOW_LAP);
00036 cv::namedWindow(WINDOW_CAN);
00037 }
00038
00039 ~ImageEdge()
00040 {
00041 cv::destroyWindow(WINDOW_IM);
00042 cv::destroyWindow(WINDOW_SOB);
00043 cv::destroyWindow(WINDOW_LAP);
00044 cv::destroyWindow(WINDOW_CAN);
00045 }
00046
00047 void imageCb(const sensor_msgs::ImageConstPtr& msg)
00048 {
00049 cv_bridge::CvImagePtr cv_ptr;
00050 cv_bridge::CvImagePtr cv_ptr_mono;
00051 cv_bridge::CvImagePtr cv_ptr_tmp;
00052 cv_bridge::CvImagePtr cv_ptr_sobel;
00053 cv_bridge::CvImagePtr cv_ptr_lap;
00054 cv_bridge::CvImagePtr cv_ptr_can;
00055
00056 try
00057 {
00058 cv_ptr = cv_bridge::toCvCopy(msg, enc::BGR8);
00059 cv_ptr_mono = cvtColor(cv_ptr, "mono8");
00060 cv_ptr_tmp = cv_bridge::toCvCopy(msg, enc::BGR8);
00061 cv_ptr_sobel = cv_bridge::toCvCopy(msg, enc::BGR8);
00062 cv_ptr_lap = cv_bridge::toCvCopy(msg, enc::BGR8);
00063 cv_ptr_can = cvtColor(cv_ptr, "mono8");
00064 }
00065 catch (cv_bridge::Exception& e)
00066 {
00067 ROS_ERROR("cv_bridge exception: %s", e.what());
00068 return;
00069 }
00070
00071
00072 cv::Sobel(cv_ptr->image, cv_ptr_tmp->image, CV_32F, 1, 1);
00073 cv::convertScaleAbs(cv_ptr_tmp->image, cv_ptr_sobel->image, 1, 0);
00074
00075 cv::Laplacian(cv_ptr->image, cv_ptr_tmp->image, CV_32F, 3);
00076 cv::convertScaleAbs(cv_ptr_tmp->image, cv_ptr_lap->image, 1, 0);
00077
00078 cv::Canny(cv_ptr_mono->image, cv_ptr_can->image, 50, 200);
00079
00080
00081
00082
00083
00084
00085 cv::imshow(WINDOW_IM, cv_ptr->image);
00086 cv::imshow(WINDOW_SOB, cv_ptr_sobel->image);
00087 cv::imshow(WINDOW_LAP, cv_ptr_lap->image);
00088 cv::imshow(WINDOW_CAN, cv_ptr_can->image);
00089 cv::waitKey(3);
00090
00091 image_pub_.publish(cv_ptr->toImageMsg());
00092 }
00093 };
00094
00095 int main(int argc, char** argv)
00096 {
00097 ros::init(argc, argv, "image_edge");
00098 ImageEdge ic;
00099 ros::spin();
00100 return 0;
00101 }