my_subscriber.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <image_transport/image_transport.h>
00003 #include <opencv2/highgui/highgui.hpp>
00004 #include <cv_bridge/cv_bridge.h>
00005 
00006 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00007 {
00008   try
00009   {
00010     cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
00011     cv::waitKey(10);
00012   }
00013   catch (cv_bridge::Exception& e)
00014   {
00015     ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
00016   }
00017 }
00018 
00019 int main(int argc, char **argv)
00020 {
00021   ros::init(argc, argv, "image_listener");
00022   ros::NodeHandle nh;
00023   cv::namedWindow("view");
00024   cv::startWindowThread();
00025   image_transport::ImageTransport it(nh);
00026   image_transport::Subscriber sub = it.subscribe("camera/image", 1, imageCallback);
00027   ros::spin();
00028   cv::destroyWindow("view");
00029 }


image_transport
Author(s): Patrick Mihelich
autogenerated on Thu Jun 6 2019 21:19:55