mirror of
https://github.com/CircusMonkey/ros_rtsp.git
synced 2025-01-28 10:48:21 -04:00
Add option for custom port and fix indentation
This commit is contained in:
parent
978484a774
commit
75290a64bc
@ -1,4 +1,5 @@
|
|||||||
# Set up your streams to rtsp here.
|
# Set up your streams to rtsp here.
|
||||||
|
port: "8554"
|
||||||
streams: # Cannot rename - must leave this as is.
|
streams: # Cannot rename - must leave this as is.
|
||||||
|
|
||||||
stream-x:
|
stream-x:
|
||||||
|
@ -12,6 +12,7 @@ namespace image2rtsp {
|
|||||||
void print_error(char *s);
|
void print_error(char *s);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
std::string port;
|
||||||
std::map<std::string, ros::Subscriber> subs;
|
std::map<std::string, ros::Subscriber> subs;
|
||||||
std::map<std::string, GstAppSrc*> appsrc;
|
std::map<std::string, GstAppSrc*> appsrc;
|
||||||
std::map<std::string, int> num_of_clients;
|
std::map<std::string, int> num_of_clients;
|
||||||
@ -19,7 +20,7 @@ namespace image2rtsp {
|
|||||||
void imageCallback(const sensor_msgs::Image::ConstPtr& msg, const std::string& topic);
|
void imageCallback(const sensor_msgs::Image::ConstPtr& msg, const std::string& topic);
|
||||||
void video_mainloop_start();
|
void video_mainloop_start();
|
||||||
void rtsp_server_add_url(const char *url, const char *sPipeline, GstElement **appsrc);
|
void rtsp_server_add_url(const char *url, const char *sPipeline, GstElement **appsrc);
|
||||||
GstRTSPServer *rtsp_server_create();
|
GstRTSPServer *rtsp_server_create(const std::string& port);
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -28,15 +28,15 @@ void Image2RTSPNodelet::onInit() {
|
|||||||
|
|
||||||
ros::NodeHandle& nh = getPrivateNodeHandle();
|
ros::NodeHandle& nh = getPrivateNodeHandle();
|
||||||
|
|
||||||
video_mainloop_start();
|
|
||||||
rtsp_server = rtsp_server_create();
|
|
||||||
|
|
||||||
// Get the parameters from the rosparam server
|
// Get the parameters from the rosparam server
|
||||||
XmlRpc::XmlRpcValue streams;
|
XmlRpc::XmlRpcValue streams;
|
||||||
nh.getParam("streams", streams);
|
nh.getParam("streams", streams);
|
||||||
ROS_ASSERT(streams.getType() == XmlRpc::XmlRpcValue::TypeStruct);
|
ROS_ASSERT(streams.getType() == XmlRpc::XmlRpcValue::TypeStruct);
|
||||||
|
|
||||||
ROS_DEBUG("Number of RTSP streams: %d", streams.size());
|
ROS_DEBUG("Number of RTSP streams: %d", streams.size());
|
||||||
|
nh.getParam("port", this->port);
|
||||||
|
|
||||||
|
video_mainloop_start();
|
||||||
|
rtsp_server = rtsp_server_create(port);
|
||||||
|
|
||||||
// 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)
|
||||||
@ -74,7 +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());
|
NODELET_INFO("Stream available at rtsp://%s:%s%s", gst_rtsp_server_get_address(rtsp_server), port.c_str(), mountpoint.c_str());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -73,12 +73,15 @@ static gboolean session_cleanup(Image2RTSPNodelet *nodelet, gboolean ignored)
|
|||||||
return TRUE;
|
return TRUE;
|
||||||
}
|
}
|
||||||
|
|
||||||
GstRTSPServer *Image2RTSPNodelet::rtsp_server_create() {
|
GstRTSPServer *Image2RTSPNodelet::rtsp_server_create(const std::string& port) {
|
||||||
GstRTSPServer *server;
|
GstRTSPServer *server;
|
||||||
|
|
||||||
/* create a server instance */
|
/* create a server instance */
|
||||||
server = gst_rtsp_server_new();
|
server = gst_rtsp_server_new();
|
||||||
|
|
||||||
|
// char *port = (char *) port;
|
||||||
|
g_object_set(server, "service", port.c_str(), NULL);
|
||||||
|
|
||||||
/* attach the server to the default maincontext */
|
/* attach the server to the default maincontext */
|
||||||
gst_rtsp_server_attach(server, NULL);
|
gst_rtsp_server_attach(server, NULL);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user