From ee41164aec469066475efd62c41b2b4e07ea6e5e Mon Sep 17 00:00:00 2001 From: Jonathan Bohren Date: Mon, 28 Jul 2014 19:47:20 -0400 Subject: [PATCH] Fixing preproc switches so that the 1.0 branch still builds against 0.1 without the switch flags --- src/gscam.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/gscam.cpp b/src/gscam.cpp index 552ac6f..d0c6cc9 100644 --- a/src/gscam.cpp +++ b/src/gscam.cpp @@ -283,7 +283,7 @@ namespace gscam { guint8* &buf_data = info.data; #else GstBuffer* buf = gst_app_sink_pull_buffer(GST_APP_SINK(sink_)); - gsize &buf_size = buf->size; + guint &buf_size = buf->size; guint8* &buf_data = buf->data; #endif GstClockTime bt = gst_element_get_base_time(pipeline_); @@ -311,7 +311,11 @@ namespace gscam { // Get the image width and height GstPad* pad = gst_element_get_static_pad(sink_, "sink"); +#if (GST_VERSION_MAJOR == 1) const GstCaps *caps = gst_pad_get_current_caps(pad); +#else + const GstCaps *caps = gst_pad_get_negotiated_caps(pad); +#endif GstStructure *structure = gst_caps_get_structure(caps,0); gst_structure_get_int(structure,"width",&width_); gst_structure_get_int(structure,"height",&height_); @@ -321,7 +325,11 @@ namespace gscam { sensor_msgs::CameraInfoPtr cinfo; cinfo.reset(new sensor_msgs::CameraInfo(cur_cinfo)); if (use_gst_timestamps_) { +#if (GST_VERSION_MAJOR == 1) cinfo->header.stamp = ros::Time(GST_TIME_AS_USECONDS(buf->pts+bt)/1e6+time_offset_); +#else + cinfo->header.stamp = ros::Time(GST_TIME_AS_USECONDS(buf->timestamp+bt)/1e6+time_offset_); +#endif } else { cinfo->header.stamp = ros::Time::now(); }