diff --git a/CMakeLists.txt b/CMakeLists.txt index 4d80953..98166b7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,8 +4,20 @@ project(gscam) # System Dependencies find_package(PkgConfig) -pkg_check_modules(GSTREAMER REQUIRED gstreamer-0.10) -pkg_check_modules(GST_APP REQUIRED gstreamer-app-0.10) + +pkg_check_modules(GSTREAMER QUIET gstreamer-0.10) +if(NOT GSTREAMER_FOUND) + set(GSTREAMER_VERSION_1_x TRUE) +endif() +if(GSTREAMER_VERSION_1_x) + message(STATUS "gst 1.0") + pkg_check_modules(GSTREAMER REQUIRED gstreamer-1.0) + pkg_check_modules(GST_APP REQUIRED gstreamer-app-1.0) +else() + message(STATUS "gst 0.1") + pkg_check_modules(GSTREAMER REQUIRED gstreamer-0.10) + pkg_check_modules(GST_APP REQUIRED gstreamer-app-0.10) +endif() if(USE_ROSBUILD) # Use rosbuild diff --git a/README.md b/README.md index 907ba88..532ecbc 100644 --- a/README.md +++ b/README.md @@ -11,6 +11,47 @@ for more ROS-like configuration and more control over the GStreamer interface. Note that this pacakge can be built both in a rosbuild and catkin workspaces. +GStreamer Library Support +------------------------- + +gscam supports the following versions of GStreamer + +### 0.1.x: _Default_ + +Install dependencies via `rosdep`. + +### 1.0.x: Experimental + +#### Dependencies: + +* gstreamer1.0-tools +* libgstreamer1.0-dev +* libgstreamer-plugins-base1.0-dev +* libgstreamer-plugins-good1.0-dev + +Ubuntu Install: + +##### 12.04 + +```sh +sudo add-apt-repository ppa:gstreamer-developers/ppa +sudo apt-get install gstreamer1.0-tools libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev libgstreamer-plugins-good1.0-dev +``` + +##### 14.04 + +```sh +sudo apt-get install gstreamer1.0-tools libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev libgstreamer-plugins-good1.0-dev +``` + +#### Usage: +* Use the CMake flag `-DGSTREAMER_VERSION_1_x=On` when building +* See the [Video4Linux2 launchfile example](examples/v4l.launch) for + an example of the differences in the GStreamer config lines + +#### Notes: +* This has been tested with `v4l2src` + ROS API (stable) ---------------- @@ -19,22 +60,22 @@ ROS API (stable) This can be run as both a node and a nodelet. #### Nodes - * `gscam` +* `gscam` #### Topics - * `camera/image_raw` - * `camera/camera_info` +* `camera/image_raw` +* `camera/camera_info` #### Services - * `camera/set_camera_info` +* `camera/set_camera_info` #### Parameters - * `~camera_name`: The name of the camera (corrsponding to the camera info) - * `~camera_info_url`: A url (`file://path/to/file`, `package://pkg_name/path/to/file`) to the [camera calibration file](http://www.ros.org/wiki/camera_calibration_parsers#File_formats). - * `~gscam_config`: The GStreamer [configuration string](http://wiki.oz9aec.net/index.php?title=Gstreamer_cheat_sheet&oldid=1829). - * `~frame_id`: The [TF](http://www.ros.org/wiki/tf) frame ID. - * `~reopen_on_eof`: Re-open the stream if it ends (EOF). - * `~sync_sink`: Synchronize the app sink (sometimes setting this to `false` can resolve problems with sub-par framerates). +* `~camera_name`: The name of the camera (corrsponding to the camera info) +* `~camera_info_url`: A url (`file://path/to/file`, `package://pkg_name/path/to/file`) to the [camera calibration file](http://www.ros.org/wiki/camera_calibration_parsers#File_formats). +* `~gscam_config`: The GStreamer [configuration string](http://wiki.oz9aec.net/index.php?title=Gstreamer_cheat_sheet&oldid=1829). +* `~frame_id`: The [TF](http://www.ros.org/wiki/tf) frame ID. +* `~reopen_on_eof`: Re-open the stream if it ends (EOF). +* `~sync_sink`: Synchronize the app sink (sometimes setting this to `false` can resolve problems with sub-par framerates). C++ API (unstable) ------------------ @@ -46,11 +87,13 @@ Examples See example launchfiles and configs in the examples directory. Currently there are examples for: - * [Video4Linux2](examples/v4l.launch): Standard - [video4linux](http://en.wikipedia.org/wiki/Video4Linux)-based cameras like - USB webcams - * [Nodelet](examples/gscam_nodelet.launch): Run a V4L-based camera in a nodelet - * [Video File](examples/videofile.launch): Any videofile readable by GStreamer - * [DeckLink](examples/decklink.launch): - [BlackMagic](http://www.blackmagicdesign.com/products/decklink/models) - DeckLink SDI capture cards (note: this requires the `gst-plugins-bad` plugins) + +* [Video4Linux2](examples/v4l.launch): Standard + [video4linux](http://en.wikipedia.org/wiki/Video4Linux)-based cameras like + USB webcams. + * ***GST-1.0:*** Use the roslaunch argument `GST10:=True` for GStreamer 1.0 variant +* [Nodelet](examples/gscam_nodelet.launch): Run a V4L-based camera in a nodelet +* [Video File](examples/videofile.launch): Any videofile readable by GStreamer +* [DeckLink](examples/decklink.launch): + [BlackMagic](http://www.blackmagicdesign.com/products/decklink/models) + DeckLink SDI capture cards (note: this requires the `gst-plugins-bad` plugins) diff --git a/examples/v4l.launch b/examples/v4l.launch index 52a4107..662e69f 100644 --- a/examples/v4l.launch +++ b/examples/v4l.launch @@ -6,11 +6,13 @@ + - + + diff --git a/manifest.xml b/manifest.xml deleted file mode 100644 index f7188ab..0000000 --- a/manifest.xml +++ /dev/null @@ -1,25 +0,0 @@ - - -A ROS camera driver that uses gstreamer to connect to devices such as webcams. - - Graylin Trevor Jay, Christopher Crick - tjay@cs.brown.edu, chriscrick@cs.brown.edu - LGPL - - - - - - - - - - - - - - - - - - diff --git a/package.xml b/package.xml index c4f9e8f..6581bc4 100644 --- a/package.xml +++ b/package.xml @@ -15,8 +15,8 @@ catkin - libgstreamer0.10-dev - libgstreamer-plugins-base0.10-dev + libgstreamer1.0-dev + libgstreamer-plugins-base1.0-dev nodelet cv_bridge diff --git a/rosdep.yaml b/rosdep.yaml deleted file mode 100644 index b33fd50..0000000 --- a/rosdep.yaml +++ /dev/null @@ -1,6 +0,0 @@ -libgstreamer0.10-dev: - ubuntu: - libgstreamer0.10-dev -libgstreamer-plugins-base0.10-dev: - ubuntu: - libgstreamer-plugins-base0.10-dev diff --git a/src/gscam.cpp b/src/gscam.cpp index dc96c22..d0c6cc9 100644 --- a/src/gscam.cpp +++ b/src/gscam.cpp @@ -127,14 +127,31 @@ namespace gscam { // Create RGB sink sink_ = gst_element_factory_make("appsink",NULL); - GstCaps * caps = NULL; + GstCaps * caps = gst_app_sink_get_caps(GST_APP_SINK(sink_)); + +#if (GST_VERSION_MAJOR == 1) + // http://gstreamer.freedesktop.org/data/doc/gstreamer/head/pwg/html/section-types-definitions.html + if (image_encoding_ == sensor_msgs::image_encodings::RGB8) { + caps = gst_caps_new_simple( "video/x-raw", + "format", G_TYPE_STRING, "RGB", + NULL); + } else if (image_encoding_ == sensor_msgs::image_encodings::MONO8) { + caps = gst_caps_new_simple( "video/x-raw", + "format", G_TYPE_STRING, "GRAY8", + NULL); + } else if (image_encoding_ == "jpeg") { + caps = gst_caps_new_simple("image/jpeg", NULL, NULL); + } +#else if (image_encoding_ == sensor_msgs::image_encodings::RGB8) { - caps = gst_caps_new_simple("video/x-raw-rgb", NULL); + caps = gst_caps_new_simple( "video/x-raw-rgb", NULL,NULL); } else if (image_encoding_ == sensor_msgs::image_encodings::MONO8) { - caps = gst_caps_new_simple("video/x-raw-gray", NULL); + caps = gst_caps_new_simple("video/x-raw-gray", NULL, NULL); } else if (image_encoding_ == "jpeg") { - caps = gst_caps_new_simple("image/jpeg", NULL); + caps = gst_caps_new_simple("image/jpeg", NULL, NULL); } +#endif + gst_app_sink_set_caps(GST_APP_SINK(sink_), caps); gst_caps_unref(caps); @@ -246,11 +263,29 @@ namespace gscam { ROS_INFO("Started stream."); // Poll the data as fast a spossible - while(ros::ok()) { + while(ros::ok()) + { // This should block until a new frame is awake, this way, we'll run at the // actual capture framerate of the device. // ROS_DEBUG("Getting data..."); +#if (GST_VERSION_MAJOR == 1) + GstSample* sample = gst_app_sink_pull_sample(GST_APP_SINK(sink_)); + if(!sample) { + ROS_ERROR("Could not get gstreamer sample."); + break; + } + GstBuffer* buf = gst_sample_get_buffer(sample); + GstMemory *memory = gst_buffer_get_memory(buf, 0); + GstMapInfo info; + + gst_memory_map(memory, &info, GST_MAP_READ); + gsize &buf_size = info.size; + guint8* &buf_data = info.data; +#else GstBuffer* buf = gst_app_sink_pull_buffer(GST_APP_SINK(sink_)); + guint &buf_size = buf->size; + guint8* &buf_data = buf->data; +#endif GstClockTime bt = gst_element_get_base_time(pipeline_); // ROS_INFO("New buffer: timestamp %.6f %lu %lu %.3f", // GST_TIME_AS_USECONDS(buf->timestamp+bt)/1e6+time_offset_, buf->timestamp, bt, time_offset_); @@ -276,16 +311,25 @@ 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_); // Update header information + sensor_msgs::CameraInfo cur_cinfo = camera_info_manager_.getCameraInfo(); sensor_msgs::CameraInfoPtr cinfo; - cinfo.reset(new sensor_msgs::CameraInfo(camera_info_manager_.getCameraInfo())); + 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(); } @@ -295,8 +339,8 @@ namespace gscam { sensor_msgs::CompressedImagePtr img(new sensor_msgs::CompressedImage()); img->header = cinfo->header; img->format = "jpeg"; - img->data.resize(buf->size); - std::copy(buf->data, (buf->data)+(buf->size), + img->data.resize(buf_size); + std::copy(buf_data, (buf_data)+(buf_size), img->data.begin()); jpeg_pub_.publish(img); cinfo_pub_.publish(cinfo); @@ -307,10 +351,10 @@ namespace gscam { ? width_ * height_ * 3 : width_ * height_; - if (buf->size < expected_frame_size) { + if (buf_size < expected_frame_size) { ROS_WARN_STREAM( "GStreamer image buffer underflow: Expected frame to be " << expected_frame_size << " bytes but got only " - << (buf->size) << " bytes. (make sure frames are correctly encoded)"); + << (buf_size) << " bytes. (make sure frames are correctly encoded)"); } // Construct Image message @@ -334,8 +378,8 @@ namespace gscam { img->step = width_; } std::copy( - buf->data, - (buf->data)+(buf->size), + buf_data, + (buf_data)+(buf_size), img->data.begin()); // Publish the image/info @@ -343,7 +387,13 @@ namespace gscam { } // Release the buffer - gst_buffer_unref(buf); + if(buf) { +#if (GST_VERSION_MAJOR == 1) + gst_memory_unmap(memory, &info); + gst_memory_unref(memory); +#endif + gst_buffer_unref(buf); + } ros::spinOnce(); }