mirror of
https://github.com/CircusMonkey/ros_rtsp.git
synced 2025-01-15 04:48:20 -04:00
improve info messages on startup, remove usb_cam node from launch
This commit is contained in:
parent
9948cdb999
commit
a204ca7d26
11
launch/rtsp_streams.launch
Normal file
11
launch/rtsp_streams.launch
Normal file
@ -0,0 +1,11 @@
|
|||||||
|
<launch>
|
||||||
|
|
||||||
|
<!-- Start the RTSP server -->
|
||||||
|
<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">
|
||||||
|
<!-- Read the stream setup file -->
|
||||||
|
<rosparam command="load" file="$(find ros_rtsp)/config/stream_setup.yaml" />
|
||||||
|
</node>
|
||||||
|
|
||||||
|
</launch>
|
@ -1,22 +0,0 @@
|
|||||||
<launch>
|
|
||||||
<!-- Start the image publisher/s if required -->
|
|
||||||
<node name="usb_cam1" pkg="usb_cam" type="usb_cam_node" output="screen" >
|
|
||||||
<param name="video_device" value="/dev/video1" />
|
|
||||||
<param name="image_width" value="640" />
|
|
||||||
<param name="image_height" value="480" />
|
|
||||||
<param name="pixel_format" value="yuyv" />
|
|
||||||
<param name="camera_frame_id" value="yuyv" />
|
|
||||||
<param name="io_method" value="mmap"/>
|
|
||||||
<param name="autofocus" value="true"/>
|
|
||||||
</node>
|
|
||||||
|
|
||||||
|
|
||||||
<!-- Start the RTSP server -->
|
|
||||||
<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">
|
|
||||||
|
|
||||||
<rosparam command="load" file="$(find ros_rtsp)/config/stream_setup.yaml" />
|
|
||||||
|
|
||||||
</node>
|
|
||||||
</launch>
|
|
@ -23,7 +23,7 @@ void Image2RTSPNodelet::onInit() {
|
|||||||
|
|
||||||
if (getenv((char*)"GST_DEBUG") == NULL) {
|
if (getenv((char*)"GST_DEBUG") == NULL) {
|
||||||
// set GST_DEBUG to warning if unset
|
// set GST_DEBUG to warning if unset
|
||||||
putenv((char*)"GST_DEBUG=*:2");
|
putenv((char*)"GST_DEBUG=*:1");
|
||||||
}
|
}
|
||||||
|
|
||||||
ros::NodeHandle& nh = getPrivateNodeHandle();
|
ros::NodeHandle& nh = getPrivateNodeHandle();
|
||||||
@ -36,13 +36,13 @@ void Image2RTSPNodelet::onInit() {
|
|||||||
nh.getParam("streams", streams);
|
nh.getParam("streams", streams);
|
||||||
ROS_ASSERT(streams.getType() == XmlRpc::XmlRpcValue::TypeStruct);
|
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
|
// Go through and parse each stream
|
||||||
for(XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = streams.begin(); it != streams.end(); ++it)
|
for(XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = streams.begin(); it != streams.end(); ++it)
|
||||||
{
|
{
|
||||||
XmlRpc::XmlRpcValue stream = streams[it->first];
|
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
|
// Convert to string for ease of use
|
||||||
mountpoint = static_cast<std::string>(stream["mountpoint"]);
|
mountpoint = static_cast<std::string>(stream["mountpoint"]);
|
||||||
@ -74,6 +74,7 @@ void Image2RTSPNodelet::onInit() {
|
|||||||
{
|
{
|
||||||
ROS_ERROR("Undefined stream type. Check your stream_setup.yaml file.");
|
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());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user