00001
00002 #include <stdlib.h>
00003 #include <unistd.h>
00004 #include <sys/ipc.h>
00005 #include <sys/shm.h>
00006
00007
00008 #include <iostream>
00009 extern "C"{
00010 #include <gst/gst.h>
00011 #include <gst/app/gstappsink.h>
00012 }
00013
00014 #include <ros/ros.h>
00015
00016 #include <image_transport/image_transport.h>
00017 #include <camera_info_manager/camera_info_manager.h>
00018
00019
00020 #include <sensor_msgs/Image.h>
00021 #include <sensor_msgs/CompressedImage.h>
00022 #include <sensor_msgs/CameraInfo.h>
00023 #include <sensor_msgs/SetCameraInfo.h>
00024 #include <sensor_msgs/image_encodings.h>
00025
00026 #include <camera_calibration_parsers/parse_ini.h>
00027
00028 #include <gscam/gscam.h>
00029
00030 namespace gscam {
00031
00032 GSCam::GSCam(ros::NodeHandle nh_camera, ros::NodeHandle nh_private) :
00033 gsconfig_(""),
00034 pipeline_(NULL),
00035 sink_(NULL),
00036 nh_(nh_camera),
00037 nh_private_(nh_private),
00038 image_transport_(nh_camera),
00039 camera_info_manager_(nh_camera)
00040 {
00041 }
00042
00043 GSCam::~GSCam()
00044 {
00045 }
00046
00047 bool GSCam::configure()
00048 {
00049
00050
00051 std::string gsconfig_rosparam = "";
00052 bool gsconfig_rosparam_defined = false;
00053 char *gsconfig_env = NULL;
00054
00055 gsconfig_rosparam_defined = nh_private_.getParam("gscam_config",gsconfig_rosparam);
00056 gsconfig_env = getenv("GSCAM_CONFIG");
00057
00058 if (!gsconfig_env && !gsconfig_rosparam_defined) {
00059 ROS_FATAL( "Problem getting GSCAM_CONFIG environment variable and 'gscam_config' rosparam is not set. This is needed to set up a gstreamer pipeline." );
00060 return false;
00061 } else if(gsconfig_env && gsconfig_rosparam_defined) {
00062 ROS_FATAL( "Both GSCAM_CONFIG environment variable and 'gscam_config' rosparam are set. Please only define one." );
00063 return false;
00064 } else if(gsconfig_env) {
00065 gsconfig_ = gsconfig_env;
00066 ROS_INFO_STREAM("Using gstreamer config from env: \""<<gsconfig_env<<"\"");
00067 } else if(gsconfig_rosparam_defined) {
00068 gsconfig_ = gsconfig_rosparam;
00069 ROS_INFO_STREAM("Using gstreamer config from rosparam: \""<<gsconfig_rosparam<<"\"");
00070 }
00071
00072
00073 nh_private_.param("sync_sink", sync_sink_, true);
00074 nh_private_.param("preroll", preroll_, false);
00075 nh_private_.param("use_gst_timestamps", use_gst_timestamps_, false);
00076
00077 nh_private_.param("reopen_on_eof", reopen_on_eof_, false);
00078
00079
00080 nh_private_.getParam("camera_info_url", camera_info_url_);
00081 nh_private_.getParam("camera_name", camera_name_);
00082
00083
00084 nh_private_.param("image_encoding", image_encoding_, sensor_msgs::image_encodings::RGB8);
00085 if (image_encoding_ != sensor_msgs::image_encodings::RGB8 &&
00086 image_encoding_ != sensor_msgs::image_encodings::MONO8 &&
00087 image_encoding_ != "jpeg") {
00088 ROS_FATAL_STREAM("Unsupported image encoding: " + image_encoding_);
00089 }
00090
00091 camera_info_manager_.setCameraName(camera_name_);
00092
00093 if(camera_info_manager_.validateURL(camera_info_url_)) {
00094 camera_info_manager_.loadCameraInfo(camera_info_url_);
00095 ROS_INFO_STREAM("Loaded camera calibration from "<<camera_info_url_);
00096 } else {
00097 ROS_WARN_STREAM("Camera info at: "<<camera_info_url_<<" not found. Using an uncalibrated config.");
00098 }
00099
00100
00101 if(!nh_private_.getParam("frame_id",frame_id_)){
00102 frame_id_ = "/camera_frame";
00103 ROS_WARN_STREAM("No camera frame_id set, using frame \""<<frame_id_<<"\".");
00104 nh_private_.setParam("frame_id",frame_id_);
00105 }
00106
00107 return true;
00108 }
00109
00110 bool GSCam::init_stream()
00111 {
00112 if(!gst_is_initialized()) {
00113
00114 ROS_DEBUG_STREAM( "Initializing gstreamer..." );
00115 gst_init(0,0);
00116 }
00117
00118 ROS_DEBUG_STREAM( "Gstreamer Version: " << gst_version_string() );
00119
00120 GError *error = 0;
00121
00122 pipeline_ = gst_parse_launch(gsconfig_.c_str(), &error);
00123 if (pipeline_ == NULL) {
00124 ROS_FATAL_STREAM( error->message );
00125 return false;
00126 }
00127
00128
00129 sink_ = gst_element_factory_make("appsink",NULL);
00130 GstCaps * caps = gst_app_sink_get_caps(GST_APP_SINK(sink_));
00131
00132 #if (GST_VERSION_MAJOR == 1)
00133
00134 if (image_encoding_ == sensor_msgs::image_encodings::RGB8) {
00135 caps = gst_caps_new_simple( "video/x-raw",
00136 "format", G_TYPE_STRING, "RGB",
00137 NULL);
00138 } else if (image_encoding_ == sensor_msgs::image_encodings::MONO8) {
00139 caps = gst_caps_new_simple( "video/x-raw",
00140 "format", G_TYPE_STRING, "GRAY8",
00141 NULL);
00142 } else if (image_encoding_ == "jpeg") {
00143 caps = gst_caps_new_simple("image/jpeg", NULL, NULL);
00144 }
00145 #else
00146 if (image_encoding_ == sensor_msgs::image_encodings::RGB8) {
00147 caps = gst_caps_new_simple( "video/x-raw-rgb", NULL,NULL);
00148 } else if (image_encoding_ == sensor_msgs::image_encodings::MONO8) {
00149 caps = gst_caps_new_simple("video/x-raw-gray", NULL, NULL);
00150 } else if (image_encoding_ == "jpeg") {
00151 caps = gst_caps_new_simple("image/jpeg", NULL, NULL);
00152 }
00153 #endif
00154
00155 gst_app_sink_set_caps(GST_APP_SINK(sink_), caps);
00156 gst_caps_unref(caps);
00157
00158
00159
00160
00161 gst_base_sink_set_sync(
00162 GST_BASE_SINK(sink_),
00163 (sync_sink_) ? TRUE : FALSE);
00164
00165 if(GST_IS_PIPELINE(pipeline_)) {
00166 GstPad *outpad = gst_bin_find_unlinked_pad(GST_BIN(pipeline_), GST_PAD_SRC);
00167 g_assert(outpad);
00168
00169 GstElement *outelement = gst_pad_get_parent_element(outpad);
00170 g_assert(outelement);
00171 gst_object_unref(outpad);
00172
00173 if(!gst_bin_add(GST_BIN(pipeline_), sink_)) {
00174 ROS_FATAL("gst_bin_add() failed");
00175 gst_object_unref(outelement);
00176 gst_object_unref(pipeline_);
00177 return false;
00178 }
00179
00180 if(!gst_element_link(outelement, sink_)) {
00181 ROS_FATAL("GStreamer: cannot link outelement(\"%s\") -> sink\n", gst_element_get_name(outelement));
00182 gst_object_unref(outelement);
00183 gst_object_unref(pipeline_);
00184 return false;
00185 }
00186
00187 gst_object_unref(outelement);
00188 } else {
00189 GstElement* launchpipe = pipeline_;
00190 pipeline_ = gst_pipeline_new(NULL);
00191 g_assert(pipeline_);
00192
00193 gst_object_unparent(GST_OBJECT(launchpipe));
00194
00195 gst_bin_add_many(GST_BIN(pipeline_), launchpipe, sink_, NULL);
00196
00197 if(!gst_element_link(launchpipe, sink_)) {
00198 ROS_FATAL("GStreamer: cannot link launchpipe -> sink");
00199 gst_object_unref(pipeline_);
00200 return false;
00201 }
00202 }
00203
00204
00205 GstClock * clock = gst_system_clock_obtain();
00206 ros::Time now = ros::Time::now();
00207 GstClockTime ct = gst_clock_get_time(clock);
00208 gst_object_unref(clock);
00209 time_offset_ = now.toSec() - GST_TIME_AS_USECONDS(ct)/1e6;
00210 ROS_INFO("Time offset: %.3f",time_offset_);
00211
00212 gst_element_set_state(pipeline_, GST_STATE_PAUSED);
00213
00214 if (gst_element_get_state(pipeline_, NULL, NULL, -1) == GST_STATE_CHANGE_FAILURE) {
00215 ROS_FATAL("Failed to PAUSE stream, check your gstreamer configuration.");
00216 return false;
00217 } else {
00218 ROS_DEBUG_STREAM("Stream is PAUSED.");
00219 }
00220
00221
00222 if (image_encoding_ == "jpeg") {
00223 jpeg_pub_ = nh_.advertise<sensor_msgs::CompressedImage>("camera/image_raw/compressed",1);
00224 cinfo_pub_ = nh_.advertise<sensor_msgs::CameraInfo>("camera/camera_info",1);
00225 } else {
00226 camera_pub_ = image_transport_.advertiseCamera("camera/image_raw", 1);
00227 }
00228
00229 return true;
00230 }
00231
00232 void GSCam::publish_stream()
00233 {
00234 ROS_INFO_STREAM("Publishing stream...");
00235
00236
00237 if (preroll_) {
00238 ROS_DEBUG("Performing preroll...");
00239
00240
00241
00242 gst_element_set_state(pipeline_, GST_STATE_PLAYING);
00243 if (gst_element_get_state(pipeline_, NULL, NULL, -1) == GST_STATE_CHANGE_FAILURE) {
00244 ROS_ERROR("Failed to PLAY during preroll.");
00245 return;
00246 } else {
00247 ROS_DEBUG("Stream is PLAYING in preroll.");
00248 }
00249
00250 gst_element_set_state(pipeline_, GST_STATE_PAUSED);
00251 if (gst_element_get_state(pipeline_, NULL, NULL, -1) == GST_STATE_CHANGE_FAILURE) {
00252 ROS_ERROR("Failed to PAUSE.");
00253 return;
00254 } else {
00255 ROS_INFO("Stream is PAUSED in preroll.");
00256 }
00257 }
00258
00259 if(gst_element_set_state(pipeline_, GST_STATE_PLAYING) == GST_STATE_CHANGE_FAILURE) {
00260 ROS_ERROR("Could not start stream!");
00261 return;
00262 }
00263 ROS_INFO("Started stream.");
00264
00265
00266 while(ros::ok())
00267 {
00268
00269
00270
00271 #if (GST_VERSION_MAJOR == 1)
00272 GstSample* sample = gst_app_sink_pull_sample(GST_APP_SINK(sink_));
00273 if(!sample) {
00274 ROS_ERROR("Could not get gstreamer sample.");
00275 break;
00276 }
00277 GstBuffer* buf = gst_sample_get_buffer(sample);
00278 GstMemory *memory = gst_buffer_get_memory(buf, 0);
00279 GstMapInfo info;
00280
00281 gst_memory_map(memory, &info, GST_MAP_READ);
00282 gsize &buf_size = info.size;
00283 guint8* &buf_data = info.data;
00284 #else
00285 GstBuffer* buf = gst_app_sink_pull_buffer(GST_APP_SINK(sink_));
00286 guint &buf_size = buf->size;
00287 guint8* &buf_data = buf->data;
00288 #endif
00289 GstClockTime bt = gst_element_get_base_time(pipeline_);
00290
00291
00292
00293
00294 #if 0
00295 GstFormat fmt = GST_FORMAT_TIME;
00296 gint64 current = -1;
00297
00298 Query the current position of the stream
00299 if (gst_element_query_position(pipeline_, &fmt, ¤t)) {
00300 ROS_INFO_STREAM("Position "<<current);
00301 }
00302 #endif
00303
00304
00305 if (!buf) {
00306 ROS_INFO("Stream ended.");
00307 break;
00308 }
00309
00310
00311
00312
00313 GstPad* pad = gst_element_get_static_pad(sink_, "sink");
00314 #if (GST_VERSION_MAJOR == 1)
00315 const GstCaps *caps = gst_pad_get_current_caps(pad);
00316 #else
00317 const GstCaps *caps = gst_pad_get_negotiated_caps(pad);
00318 #endif
00319 GstStructure *structure = gst_caps_get_structure(caps,0);
00320 gst_structure_get_int(structure,"width",&width_);
00321 gst_structure_get_int(structure,"height",&height_);
00322
00323
00324 sensor_msgs::CameraInfo cur_cinfo = camera_info_manager_.getCameraInfo();
00325 sensor_msgs::CameraInfoPtr cinfo;
00326 cinfo.reset(new sensor_msgs::CameraInfo(cur_cinfo));
00327 if (use_gst_timestamps_) {
00328 #if (GST_VERSION_MAJOR == 1)
00329 cinfo->header.stamp = ros::Time(GST_TIME_AS_USECONDS(buf->pts+bt)/1e6+time_offset_);
00330 #else
00331 cinfo->header.stamp = ros::Time(GST_TIME_AS_USECONDS(buf->timestamp+bt)/1e6+time_offset_);
00332 #endif
00333 } else {
00334 cinfo->header.stamp = ros::Time::now();
00335 }
00336
00337 cinfo->header.frame_id = frame_id_;
00338 if (image_encoding_ == "jpeg") {
00339 sensor_msgs::CompressedImagePtr img(new sensor_msgs::CompressedImage());
00340 img->header = cinfo->header;
00341 img->format = "jpeg";
00342 img->data.resize(buf_size);
00343 std::copy(buf_data, (buf_data)+(buf_size),
00344 img->data.begin());
00345 jpeg_pub_.publish(img);
00346 cinfo_pub_.publish(cinfo);
00347 } else {
00348
00349 const unsigned int expected_frame_size =
00350 image_encoding_ == sensor_msgs::image_encodings::RGB8
00351 ? width_ * height_ * 3
00352 : width_ * height_;
00353
00354 if (buf_size < expected_frame_size) {
00355 ROS_WARN_STREAM( "GStreamer image buffer underflow: Expected frame to be "
00356 << expected_frame_size << " bytes but got only "
00357 << (buf_size) << " bytes. (make sure frames are correctly encoded)");
00358 }
00359
00360
00361 sensor_msgs::ImagePtr img(new sensor_msgs::Image());
00362
00363 img->header = cinfo->header;
00364
00365
00366 img->width = width_;
00367 img->height = height_;
00368 img->encoding = image_encoding_;
00369 img->is_bigendian = false;
00370 img->data.resize(expected_frame_size);
00371
00372
00373
00374
00375 if (image_encoding_ == sensor_msgs::image_encodings::RGB8) {
00376 img->step = width_ * 3;
00377 } else {
00378 img->step = width_;
00379 }
00380 std::copy(
00381 buf_data,
00382 (buf_data)+(buf_size),
00383 img->data.begin());
00384
00385
00386 camera_pub_.publish(img, cinfo);
00387 }
00388
00389
00390 if(buf) {
00391 #if (GST_VERSION_MAJOR == 1)
00392 gst_memory_unmap(memory, &info);
00393 gst_memory_unref(memory);
00394 #endif
00395 gst_buffer_unref(buf);
00396 }
00397
00398 ros::spinOnce();
00399 }
00400 }
00401
00402 void GSCam::cleanup_stream()
00403 {
00404
00405 ROS_INFO("Stopping gstreamer pipeline...");
00406 if(pipeline_) {
00407 gst_element_set_state(pipeline_, GST_STATE_NULL);
00408 gst_object_unref(pipeline_);
00409 pipeline_ = NULL;
00410 }
00411 }
00412
00413 void GSCam::run() {
00414 while(ros::ok()) {
00415 if(!this->configure()) {
00416 ROS_FATAL("Failed to configure gscam!");
00417 break;
00418 }
00419
00420 if(!this->init_stream()) {
00421 ROS_FATAL("Failed to initialize gscam stream!");
00422 break;
00423 }
00424
00425
00426 this->publish_stream();
00427
00428 this->cleanup_stream();
00429
00430 ROS_INFO("GStreamer stream stopped!");
00431
00432 if(reopen_on_eof_) {
00433 ROS_INFO("Reopening stream...");
00434 } else {
00435 ROS_INFO("Cleaning up stream and exiting...");
00436 break;
00437 }
00438 }
00439
00440 }
00441
00442
00443
00444 void gst_eos_cb(GstAppSink *appsink, gpointer user_data ) {
00445 }
00446 GstFlowReturn gst_new_preroll_cb(GstAppSink *appsink, gpointer user_data ) {
00447 return GST_FLOW_OK;
00448 }
00449 GstFlowReturn gst_new_asample_cb(GstAppSink *appsink, gpointer user_data ) {
00450 return GST_FLOW_OK;
00451 }
00452
00453 }