diff --git a/launch/rtsp_streams.launch b/launch/rtsp_streams.launch
new file mode 100644
index 0000000..eac359d
--- /dev/null
+++ b/launch/rtsp_streams.launch
@@ -0,0 +1,11 @@
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/test_rtsp.launch b/launch/test_rtsp.launch
deleted file mode 100644
index db54976..0000000
--- a/launch/test_rtsp.launch
+++ /dev/null
@@ -1,22 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/src/image2rtsp.cpp b/src/image2rtsp.cpp
index 673eb8a..980953e 100644
--- a/src/image2rtsp.cpp
+++ b/src/image2rtsp.cpp
@@ -23,7 +23,7 @@ void Image2RTSPNodelet::onInit() {
if (getenv((char*)"GST_DEBUG") == NULL) {
// set GST_DEBUG to warning if unset
- putenv((char*)"GST_DEBUG=*:2");
+ putenv((char*)"GST_DEBUG=*:1");
}
ros::NodeHandle& nh = getPrivateNodeHandle();
@@ -36,13 +36,13 @@ void Image2RTSPNodelet::onInit() {
nh.getParam("streams", streams);
ROS_ASSERT(streams.getType() == XmlRpc::XmlRpcValue::TypeStruct);
- ROS_INFO("Number of RTSP streams: %d", streams.size());
+ ROS_DEBUG("Number of RTSP streams: %d", streams.size());
// Go through and parse each stream
for(XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = streams.begin(); it != streams.end(); ++it)
{
XmlRpc::XmlRpcValue stream = streams[it->first];
- ROS_INFO_STREAM("Found stream: " << (std::string)(it->first) << " ==> " << stream);
+ ROS_DEBUG_STREAM("Found stream: " << (std::string)(it->first) << " ==> " << stream);
// Convert to string for ease of use
mountpoint = static_cast(stream["mountpoint"]);
@@ -74,6 +74,7 @@ void Image2RTSPNodelet::onInit() {
{
ROS_ERROR("Undefined stream type. Check your stream_setup.yaml file.");
}
+ NODELET_INFO("Stream available at rtsp://%s:8554%s", gst_rtsp_server_get_address(rtsp_server), mountpoint.c_str());
}
}