Use yaml to set rtsp streams

This commit is contained in:
Sam Armstrong 2018-09-26 00:13:36 +10:00
parent 9acf1b3528
commit 6be5c6c9b4
3 changed files with 47 additions and 13 deletions

11
config/stream_setup.yaml Normal file
View File

@ -0,0 +1,11 @@
streams:
stream1:
name: stream1
type: cam
source: /dev/video0
mountpoint: /front
stream2:
name: stream2
type: topic
source: /usb_cam/image_raw
mountpoint: /back

View File

@ -1,6 +1,6 @@
<launch>
<!-- Start the image publisher -->
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<!-- <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
@ -8,14 +8,15 @@
<param name="camera_frame_id" value="yuyv" />
<param name="io_method" value="mmap"/>
<param name="autofocus" value="true"/>
</node>
</node> -->
<!-- <node pkg="ros_rtsp" name="camera_publisher" type="camera_publisher" args="0"/> -->
<node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen"/>
<node pkg="nodelet" type="nodelet" name="Image2RTSPNodelet" args="load image2rtsp/Image2RTSPNodelet standalone_nodelet" output="screen">
<param name="topic_1" type="str" value="/usb_cam/image_raw" />
<param name="mountpoint_1" type="str" value="/front" />
<rosparam command="load" file="/home/samar/co/reid_ws/src/ros_rtsp/config/stream_setup.yaml" />
<param name="pipeline_1" type="str" value="( appsrc name=imagesrc do-timestamp=true max-latency=50 max-bytes=1000 is-live=true ! videoconvert ! videoscale ! video/x-raw,width=800,height=640 ! videoconvert ! videorate ! video/x-raw,framerate=10/1 ! queue ! x264enc tune=zerolatency bitrate=1000 key-int-max=90 ! video/x-h264, profile=baseline ! rtph264pay name=pay0 pt=96 )" />
</node>
</launch>

View File

@ -16,8 +16,9 @@ using namespace image2rtsp;
void Image2RTSPNodelet::onInit() {
string mountpoint_1;
string pipeline_1;
string pipeline_cam = "( appsrc name=imagesrc do-timestamp=true max-latency=50 max-bytes=1000 is-live=true ! videoconvert ! videoscale ! video/x-raw,width=800,height=640 ! videoconvert ! videorate ! video/x-raw,framerate=10/1 ! queue ! x264enc tune=zerolatency bitrate=1000 key-int-max=90 ! video/x-h264, profile=baseline ! rtph264pay name=pay0 pt=96 )";
string pipeline_appsrc = "( appsrc name=imagesrc do-timestamp=true max-latency=50 max-bytes=1000 is-live=true ! videoconvert ! videoscale ! video/x-raw,width=800,height=640 ! videoconvert ! videorate ! video/x-raw,framerate=10/1 ! queue ! x264enc tune=zerolatency bitrate=1000 key-int-max=90 ! video/x-h264, profile=baseline ! rtph264pay name=pay0 pt=96 )";
NODELET_DEBUG("Initializing image2rtsp nodelet...");
@ -28,15 +29,36 @@ void Image2RTSPNodelet::onInit() {
num = 0;
appsrc = NULL;
ros::NodeHandle& node = getPrivateNodeHandle();
ros::NodeHandle& nh = getPrivateNodeHandle();
video_mainloop_start();
rtsp_server = rtsp_server_create();
node.getParam("mountpoint_1", mountpoint_1);
node.getParam("pipeline_1", pipeline_1);
XmlRpc::XmlRpcValue streams;
nh.getParam("streams", streams);
ROS_ASSERT(streams.getType() == XmlRpc::XmlRpcValue::TypeStruct);
ROS_INFO("Number of streams: %d", streams.size());
for(XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = streams.begin(); it != streams.end(); ++it)
{
ROS_INFO_STREAM("Found stream: " << (std::string)(it->first) << " ==> " << streams[it->first]);
if (streams[it->first]["type"]=="cam")
{
ROS_INFO("ADDING CAMERA");
rtsp_server_add_url(static_cast<std::string>(streams[it->first]["mountpoint"]).c_str(), pipeline_cam.c_str(), NULL);
}
else if (streams[it->first]["type"]=="topic")
{
ROS_INFO("ADDING topic");
rtsp_server_add_url(static_cast<std::string>(streams[it->first]["mountpoint"]).c_str(), pipeline_appsrc.c_str(), (GstElement **)&appsrc);
}
}
rtsp_server_add_url(mountpoint_1.c_str(), pipeline_1.c_str(), (GstElement **)&appsrc);
}
/* Borrowed from https://github.com/ProjectArtemis/gst_video_server/blob/master/src/server_nodelet.cpp */
@ -151,9 +173,9 @@ void Image2RTSPNodelet::url_connected(string url) {
if (url == "/front") {
if (num == 0) {
ros::NodeHandle& node = getPrivateNodeHandle();
node.getParam("topic_1", topic);
sub = node.subscribe(topic, 10, &Image2RTSPNodelet::imageCallback, this);
ros::NodeHandle& nh = getPrivateNodeHandle();
nh.getParam("topic_1", topic);
sub = nh.subscribe(topic, 10, &Image2RTSPNodelet::imageCallback, this);
}
num++;
}