This is a ROS package originally developed by the Brown Robotics
Lab for broadcasting any
GStreamer-based video stream via the
standard ROS Camera API. This fork has
several fixes incorporated into it to make it broadcast correct
sensor_msgs/Image
messages with proper frames and timestamps. It also allows
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.
- Convert YUV to RGB/BGR with low CPU usage (50% on ORIN AGX with 5M Camera, still room for optimization)
- Publish Camera INFO
- Get the timestamp of the camera itself (gst can get V4L2 timestamp, but need to verify)
- Use hardware acceleration
- Support Nodelet
- Support Resize
- Support RTSP Camera
(Tested on ORIN AGX with Ubuntu20.04)
- gstreamer1.0-tools
- libgstreamer1.0-dev
- libgstreamer-plugins-base1.0-dev
- libgstreamer-plugins-good1.0-dev
- gstreamer1.0-plugins-bad
- v4l-utils
Ubuntu Install (≥14.04):
$ sudo apt-get install gstreamer1.0-tools libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev libgstreamer-plugins-good1.0-dev gstreamer1.0-plugins-bad v4l-utils
Just try to simply show the GMSL camera:
$ gst-launch-1.0 v4l2src device={DEVICE} ! 'video/x-raw,format={FORMAT},width={WIDTH},height={HEIGHT},framerate={FPS}/1' ! videoconvert ! fpsdisplaysink video-sink=xvimagesink sync=false
Or RTSP camera:
$ gst-launch-1.0 rtspsrc location=rtsp://{user}:{password}@{url} latency=0 ! rtph264depay ! h264parse ! avdec_h264 ! autovideoconvert ! autovideosink sync=false
Example:
# GMSL Camera
$ gst-launch-1.0 v4l2src device=/dev/video0 ! 'video/x-raw,format=UYVY,width=2880,height=1860,framerate=30/1' ! videoconvert ! fpsdisplaysink video-sink=xvimagesink sync=false
# RTSP Camera
$ gst-launch-1.0 rtspsrc location=rtsp://admin:[email protected]:554/Streaming/Channels/101 latency=0 ! rtph264depay ! h264parse ! avdec_h264 ! videoconvert ! fpsdisplaysink video-sink=xvimagesink sync=false
-
Compile the package:
$ catkin build gscam
-
Test nvv4l2camerasrc and nvvidconv (Necessary):
$ gst-launch-1.0 nvv4l2camerasrc device={DEVICE} ! 'video/x-raw(memory:NVMM),format={FORMAT},width={WIDTH},height={HEIGHT},framerate={FPS}/1' ! nvvidconv ! video/x-raw,format=BGRx ! videoconvert ! fpsdisplaysink video-sink=xvimagesink sync=false
If the image is distorted, please execute
$ v4l2-ctl -d /dev/video0 --set-ctrl preferred_stride={STRIDE}
, The{STRIDE}
parameter is calculated according tocell({WIDTH} * 2/256) * 256
; For example{WIDTH}=2880
, then the calculation process is:cell(2880 * 2/256) * 256 = 23 * 256=5888
. More information please see this issue. -
See GMSL sample launch file and run with:
$ roslaunch gscam gmsl.launch
- Currently testing a 5M Camera on ORIN AGX: it occupies about 46% of the CPU single core when it is unloaded, about 70% of the CPU single core when reading image_raw, and about 150% of the CPU when reading compressed.
- Due to the limited output format supported by nvvidconv, the final conversion to RGB8 and BGR8 still runs on the CPU.
This can be run as both a node and a nodelet.
gscam
camera/image_raw
camera/camera_info
camera/set_camera_info
~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.~gscam_config
: The GStreamer configuration string.~frame_id
: The TF frame ID.~reopen_on_eof
: Re-open the stream if it ends (EOF).~sync_sink
: Synchronize the app sink (sometimes setting this tofalse
can resolve problems with sub-par framerates).~image_encoding
: Encoding of the stream. Can be {rgb8
,bgr8
,mono8
}. Defaults torgb8
. (Verify with:$ rostopic echo /camera/image_raw | grep encoding
)
WARNING: erroneous pipeline: no element "h264parse": $ sudo apt-get install gstreamer1.0-plugins-bad
See example launchfiles and configs in the examples directory. Currently there are examples for:
- Video4Linux2: Standard
video4linux-based cameras like
USB webcams.
- GST-1.0: Use the roslaunch argument
GST10:=True
for GStreamer 1.0 variant
- GST-1.0: Use the roslaunch argument
- Nodelet: Run a V4L-based camera in a nodelet
- Video File: Any videofile readable by GStreamer
- DeckLink:
BlackMagic
DeckLink SDI capture cards (note: this requires the
gst-plugins-bad
plugins)