gscam.h
Go to the documentation of this file.
1 #ifndef __GSCAM_GSCAM_H
2 #define __GSCAM_GSCAM_H
3 
4 extern "C"{
5 #include <gst/gst.h>
6 #include <gst/app/gstappsink.h>
7 }
8 
9 #include <ros/ros.h>
10 
13 
14 #include <sensor_msgs/Image.h>
15 #include <sensor_msgs/CameraInfo.h>
16 #include <sensor_msgs/SetCameraInfo.h>
17 
18 #include <stdexcept>
19 
20 namespace gscam {
21 
22  class GSCam {
23  public:
24  GSCam(ros::NodeHandle nh_camera, ros::NodeHandle nh_private);
25  ~GSCam();
26 
27  bool configure();
28  bool init_stream();
29  void publish_stream();
30  void cleanup_stream();
31 
32  void run();
33 
34  private:
35  // General gstreamer configuration
36  std::string gsconfig_;
37 
38  // Gstreamer structures
39  GstElement *pipeline_;
40  GstElement *sink_;
41 
42  // Appsink configuration
43  bool sync_sink_;
44  bool preroll_;
47 
48  // Camera publisher configuration
49  std::string frame_id_;
51  std::string image_encoding_;
52  std::string camera_name_;
53  std::string camera_info_url_;
54 
55  // ROS Inteface
56  // Calibration between ros::Time and gst timestamps
57  double time_offset_;
62  // Case of a jpeg only publisher
65  };
66 
67 }
68 
69 #endif // ifndef __GSCAM_GSCAM_H
bool sync_sink_
Definition: gscam.h:43
std::string gsconfig_
Definition: gscam.h:36
GSCam(ros::NodeHandle nh_camera, ros::NodeHandle nh_private)
Definition: gscam.cpp:32
GstElement * pipeline_
Definition: gscam.h:39
int height_
Definition: gscam.h:50
ros::NodeHandle nh_
Definition: gscam.h:58
bool use_gst_timestamps_
Definition: gscam.h:46
bool configure()
Definition: gscam.cpp:47
ros::Publisher jpeg_pub_
Definition: gscam.h:63
ros::Publisher cinfo_pub_
Definition: gscam.h:64
bool preroll_
Definition: gscam.h:44
double time_offset_
Definition: gscam.h:57
bool init_stream()
Definition: gscam.cpp:110
image_transport::ImageTransport image_transport_
Definition: gscam.h:59
GstElement * sink_
Definition: gscam.h:40
bool reopen_on_eof_
Definition: gscam.h:45
camera_info_manager::CameraInfoManager camera_info_manager_
Definition: gscam.h:60
void cleanup_stream()
Definition: gscam.cpp:402
std::string image_encoding_
Definition: gscam.h:51
Definition: gscam.h:20
std::string camera_info_url_
Definition: gscam.h:53
int width_
Definition: gscam.h:50
void run()
Definition: gscam.cpp:413
image_transport::CameraPublisher camera_pub_
Definition: gscam.h:61
void publish_stream()
Definition: gscam.cpp:232
std::string frame_id_
Definition: gscam.h:49
ros::NodeHandle nh_private_
Definition: gscam.h:58
std::string camera_name_
Definition: gscam.h:52


gscam
Author(s): Jonathan Bohren , Graylin Trevor Jay , Christopher Crick
autogenerated on Mon Jun 10 2019 13:26:59