00001 #ifndef __GSCAM_GSCAM_H 00002 #define __GSCAM_GSCAM_H 00003 00004 extern "C"{ 00005 #include <gst/gst.h> 00006 #include <gst/app/gstappsink.h> 00007 } 00008 00009 #include <ros/ros.h> 00010 00011 #include <image_transport/image_transport.h> 00012 #include <camera_info_manager/camera_info_manager.h> 00013 00014 #include <sensor_msgs/Image.h> 00015 #include <sensor_msgs/CameraInfo.h> 00016 #include <sensor_msgs/SetCameraInfo.h> 00017 00018 #include <stdexcept> 00019 00020 namespace gscam { 00021 00022 class GSCam { 00023 public: 00024 GSCam(ros::NodeHandle nh_camera, ros::NodeHandle nh_private); 00025 ~GSCam(); 00026 00027 bool configure(); 00028 bool init_stream(); 00029 void publish_stream(); 00030 void cleanup_stream(); 00031 00032 void run(); 00033 00034 private: 00035 // General gstreamer configuration 00036 std::string gsconfig_; 00037 00038 // Gstreamer structures 00039 GstElement *pipeline_; 00040 GstElement *sink_; 00041 00042 // Appsink configuration 00043 bool sync_sink_; 00044 bool preroll_; 00045 bool reopen_on_eof_; 00046 bool use_gst_timestamps_; 00047 00048 // Camera publisher configuration 00049 std::string frame_id_; 00050 int width_, height_; 00051 std::string image_encoding_; 00052 std::string camera_name_; 00053 std::string camera_info_url_; 00054 00055 // ROS Inteface 00056 // Calibration between ros::Time and gst timestamps 00057 double time_offset_; 00058 ros::NodeHandle nh_, nh_private_; 00059 image_transport::ImageTransport image_transport_; 00060 camera_info_manager::CameraInfoManager camera_info_manager_; 00061 image_transport::CameraPublisher camera_pub_; 00062 // Case of a jpeg only publisher 00063 ros::Publisher jpeg_pub_; 00064 ros::Publisher cinfo_pub_; 00065 }; 00066 00067 } 00068 00069 #endif // ifndef __GSCAM_GSCAM_H