11 #include <gst/app/gstappsink.h> 20 #include <sensor_msgs/Image.h> 21 #include <sensor_msgs/CompressedImage.h> 22 #include <sensor_msgs/CameraInfo.h> 23 #include <sensor_msgs/SetCameraInfo.h> 37 nh_private_(nh_private),
38 image_transport_(nh_camera),
39 camera_info_manager_(nh_camera)
51 std::string gsconfig_rosparam =
"";
52 bool gsconfig_rosparam_defined =
false;
53 char *gsconfig_env = NULL;
56 gsconfig_env = getenv(
"GSCAM_CONFIG");
58 if (!gsconfig_env && !gsconfig_rosparam_defined) {
59 ROS_FATAL(
"Problem getting GSCAM_CONFIG environment variable and 'gscam_config' rosparam is not set. This is needed to set up a gstreamer pipeline." );
61 }
else if(gsconfig_env && gsconfig_rosparam_defined) {
62 ROS_FATAL(
"Both GSCAM_CONFIG environment variable and 'gscam_config' rosparam are set. Please only define one." );
64 }
else if(gsconfig_env) {
66 ROS_INFO_STREAM(
"Using gstreamer config from env: \""<<gsconfig_env<<
"\"");
67 }
else if(gsconfig_rosparam_defined) {
69 ROS_INFO_STREAM(
"Using gstreamer config from rosparam: \""<<gsconfig_rosparam<<
"\"");
112 if(!gst_is_initialized()) {
129 sink_ = gst_element_factory_make(
"appsink",NULL);
130 GstCaps * caps = gst_app_sink_get_caps(GST_APP_SINK(
sink_));
132 #if (GST_VERSION_MAJOR == 1) 135 caps = gst_caps_new_simple(
"video/x-raw",
136 "format", G_TYPE_STRING,
"RGB",
139 caps = gst_caps_new_simple(
"video/x-raw",
140 "format", G_TYPE_STRING,
"GRAY8",
143 caps = gst_caps_new_simple(
"image/jpeg", NULL, NULL);
147 caps = gst_caps_new_simple(
"video/x-raw-rgb", NULL,NULL);
149 caps = gst_caps_new_simple(
"video/x-raw-gray", NULL, NULL);
151 caps = gst_caps_new_simple(
"image/jpeg", NULL, NULL);
155 gst_app_sink_set_caps(GST_APP_SINK(
sink_), caps);
156 gst_caps_unref(caps);
161 gst_base_sink_set_sync(
162 GST_BASE_SINK(
sink_),
166 GstPad *outpad = gst_bin_find_unlinked_pad(GST_BIN(
pipeline_), GST_PAD_SRC);
169 GstElement *outelement = gst_pad_get_parent_element(outpad);
170 g_assert(outelement);
171 gst_object_unref(outpad);
175 gst_object_unref(outelement);
180 if(!gst_element_link(outelement,
sink_)) {
181 ROS_FATAL(
"GStreamer: cannot link outelement(\"%s\") -> sink\n", gst_element_get_name(outelement));
182 gst_object_unref(outelement);
187 gst_object_unref(outelement);
193 gst_object_unparent(GST_OBJECT(launchpipe));
197 if(!gst_element_link(launchpipe,
sink_)) {
198 ROS_FATAL(
"GStreamer: cannot link launchpipe -> sink");
205 GstClock * clock = gst_system_clock_obtain();
207 GstClockTime ct = gst_clock_get_time(clock);
208 gst_object_unref(clock);
212 gst_element_set_state(
pipeline_, GST_STATE_PAUSED);
214 if (gst_element_get_state(
pipeline_, NULL, NULL, -1) == GST_STATE_CHANGE_FAILURE) {
215 ROS_FATAL(
"Failed to PAUSE stream, check your gstreamer configuration.");
242 gst_element_set_state(
pipeline_, GST_STATE_PLAYING);
243 if (gst_element_get_state(
pipeline_, NULL, NULL, -1) == GST_STATE_CHANGE_FAILURE) {
244 ROS_ERROR(
"Failed to PLAY during preroll.");
247 ROS_DEBUG(
"Stream is PLAYING in preroll.");
250 gst_element_set_state(
pipeline_, GST_STATE_PAUSED);
251 if (gst_element_get_state(
pipeline_, NULL, NULL, -1) == GST_STATE_CHANGE_FAILURE) {
255 ROS_INFO(
"Stream is PAUSED in preroll.");
259 if(gst_element_set_state(
pipeline_, GST_STATE_PLAYING) == GST_STATE_CHANGE_FAILURE) {
271 #if (GST_VERSION_MAJOR == 1) 272 GstSample* sample = gst_app_sink_pull_sample(GST_APP_SINK(
sink_));
274 ROS_ERROR(
"Could not get gstreamer sample.");
277 GstBuffer* buf = gst_sample_get_buffer(sample);
278 GstMemory *memory = gst_buffer_get_memory(buf, 0);
281 gst_memory_map(memory, &info, GST_MAP_READ);
282 gsize &buf_size = info.size;
283 guint8* &buf_data = info.data;
285 GstBuffer* buf = gst_app_sink_pull_buffer(GST_APP_SINK(
sink_));
286 guint &buf_size = buf->size;
287 guint8* &buf_data = buf->data;
289 GstClockTime bt = gst_element_get_base_time(
pipeline_);
295 GstFormat fmt = GST_FORMAT_TIME;
298 Query the current position of the stream
299 if (gst_element_query_position(
pipeline_, &fmt, ¤t)) {
313 GstPad* pad = gst_element_get_static_pad(
sink_,
"sink");
314 #if (GST_VERSION_MAJOR == 1) 315 const GstCaps *caps = gst_pad_get_current_caps(pad);
317 const GstCaps *caps = gst_pad_get_negotiated_caps(pad);
319 GstStructure *structure = gst_caps_get_structure(caps,0);
320 gst_structure_get_int(structure,
"width",&
width_);
321 gst_structure_get_int(structure,
"height",&
height_);
325 sensor_msgs::CameraInfoPtr cinfo;
326 cinfo.reset(
new sensor_msgs::CameraInfo(cur_cinfo));
328 #if (GST_VERSION_MAJOR == 1) 339 sensor_msgs::CompressedImagePtr img(
new sensor_msgs::CompressedImage());
340 img->header = cinfo->header;
341 img->format =
"jpeg";
342 img->data.resize(buf_size);
343 std::copy(buf_data, (buf_data)+(buf_size),
349 const unsigned int expected_frame_size =
354 if (buf_size < expected_frame_size) {
355 ROS_WARN_STREAM(
"GStreamer image buffer underflow: Expected frame to be " 356 << expected_frame_size <<
" bytes but got only " 357 << (buf_size) <<
" bytes. (make sure frames are correctly encoded)");
361 sensor_msgs::ImagePtr img(
new sensor_msgs::Image());
363 img->header = cinfo->header;
369 img->is_bigendian =
false;
370 img->data.resize(expected_frame_size);
382 (buf_data)+(buf_size),
391 #if (GST_VERSION_MAJOR == 1) 392 gst_memory_unmap(memory, &info);
393 gst_memory_unref(memory);
395 gst_buffer_unref(buf);
405 ROS_INFO(
"Stopping gstreamer pipeline...");
407 gst_element_set_state(
pipeline_, GST_STATE_NULL);
421 ROS_FATAL(
"Failed to initialize gscam stream!");
430 ROS_INFO(
"GStreamer stream stopped!");
435 ROS_INFO(
"Cleaning up stream and exiting...");
void gst_eos_cb(GstAppSink *appsink, gpointer user_data)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
sensor_msgs::CameraInfo getCameraInfo(void)
void publish(const boost::shared_ptr< M > &message) const
GSCam(ros::NodeHandle nh_camera, ros::NodeHandle nh_private)
bool loadCameraInfo(const std::string &url)
GstFlowReturn gst_new_preroll_cb(GstAppSink *appsink, gpointer user_data)
ros::Publisher cinfo_pub_
bool validateURL(const std::string &url)
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::ImageTransport image_transport_
#define ROS_FATAL_STREAM(args)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
camera_info_manager::CameraInfoManager camera_info_manager_
std::string image_encoding_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
std::string camera_info_url_
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
image_transport::CameraPublisher camera_pub_
GstFlowReturn gst_new_asample_cb(GstAppSink *appsink, gpointer user_data)
ROSCPP_DECL void spinOnce()
ros::NodeHandle nh_private_
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
bool setCameraName(const std::string &cname)