theora_pub.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <image_transport/image_transport.h>
00003 #include <opencv/cv.h>
00004 #include <opencv/highgui.h>
00005 #include <cv_bridge/CvBridge.h>
00006   
00007 
00008 class Theora_obj
00009 {
00010   public:
00011     image_transport::Publisher pub;
00012     void callback(const sensor_msgs::ImageConstPtr& msg);
00013     void set_pub(image_transport::ImageTransport& it);
00014       
00015 };
00016 
00017 void Theora_obj::set_pub(image_transport::ImageTransport& it)
00018 {
00019     pub = it.advertise("hrl_compressed_img/image", 1);
00020 }
00021 
00022 void Theora_obj::callback(const sensor_msgs::ImageConstPtr& msg)
00023 {
00024     pub.publish(msg);
00025 }
00026 
00027 
00028 
00029 int main(int argc, char **argv)
00030 {
00031   ros::init(argc, argv, "theora_publish");
00032   ros::NodeHandle nh;
00033   image_transport::ImageTransport it(nh);
00034   Theora_obj t_obj;
00035   t_obj.set_pub(it);
00036   ros::Subscriber cam_image = nh.subscribe(argv[1], 1, &Theora_obj::callback, &t_obj);
00037 
00038   ros::spin();
00039 }
00040 
00041 


hrl_camera
Author(s): Hai Nguyen, Advait Jain, Cressel Anderson, Marc Killpack
autogenerated on Wed Nov 27 2013 11:37:01