my_publisher.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 int main(int argc, char** argv)
00007 {
00008   ros::init(argc, argv, "image_publisher");
00009   ros::NodeHandle nh;
00010   image_transport::ImageTransport it(nh);
00011   image_transport::Publisher pub = it.advertise("camera/image", 1);
00012 
00013   cv::Mat image = cv::imread(argv[1], CV_LOAD_IMAGE_COLOR);
00014   sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
00015 
00016   ros::Rate loop_rate(5);
00017   while (nh.ok()) {
00018     pub.publish(msg);
00019     ros::spinOnce();
00020     loop_rate.sleep();
00021   }
00022 }
00023 


image_transport
Author(s): Patrick Mihelich
autogenerated on Tue Jun 6 2017 02:33:36