Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <iostream>
00036 #include <string>
00037 #include <boost/thread.hpp>
00038 #include <boost/bind.hpp>
00039 #include "server.h"
00040
00041 #include "ros/ros.h"
00042
00043 #include "server_configuration.h"
00044
00045 void showConfig(const ros_http_video_streamer::ServerConfiguration& config)
00046 {
00047 std::cout << "ROS Http Video Streamer" << std::endl << std::endl;
00048 std::cout << "Settings:" << std::endl;
00049 std::cout << " Port: " << config.port_ << std::endl;
00050 std::cout << " Codec: " << config.codec_ << std::endl;
00051 std::cout << " Bitrate: " << config.bitrate_ << std::endl;
00052 std::cout << " Framerate: " << config.framerate_ << std::endl;
00053 std::cout << " Codec profile: " << config.profile_ << std::endl;
00054 std::cout << " Fileserver enabled: " << config.www_file_server_ << std::endl;
00055 std::cout << " Fileserver Root: " << config.wwwroot_ << std::endl;
00056 }
00057
00058 int main(int argc, char* argv[])
00059 {
00060 ros::init(argc, argv, "ROS_Http_Video_Streamer");
00061
00062 ROS_WARN("WARNING -- ros_web_video IS NOW DEPRECATED.");
00063 ROS_WARN("PLEASE SEE https://github.com/RobotWebTools/web_video_server.");
00064
00065
00066 ros_http_video_streamer::ServerConfiguration server_conf;
00067
00068
00069 ros::NodeHandle priv_nh_("~");
00070
00071
00072 priv_nh_.param<int>("port", server_conf.port_, server_conf.port_);
00073
00074
00075 priv_nh_.param<std::string>("codec", server_conf.codec_, server_conf.codec_);
00076
00077
00078 priv_nh_.param<int>("bitrate", server_conf.bitrate_, server_conf.bitrate_);
00079
00080
00081 priv_nh_.param<int>("framerate", server_conf.framerate_, server_conf.framerate_);
00082
00083
00084 priv_nh_.param<int>("quality", server_conf.quality_, server_conf.quality_);
00085
00086
00087 priv_nh_.param<int>("gop", server_conf.gop_, server_conf.gop_);
00088
00089
00090 priv_nh_.param<std::string>("profile", server_conf.profile_, server_conf.profile_);
00091
00092
00093 priv_nh_.param<std::string>("wwwroot", server_conf.wwwroot_, server_conf.wwwroot_);
00094
00095
00096 priv_nh_.param<std::string>("transport", server_conf.ros_transport_, server_conf.ros_transport_);
00097
00098
00099 priv_nh_.param<bool>("www_file_server", server_conf.www_file_server_, server_conf.www_file_server_);
00100
00101 showConfig(server_conf);
00102
00103 try
00104 {
00105
00106
00107 ros_http_video_streamer::server s(server_conf, 10);
00108 boost::thread t(boost::bind(&ros_http_video_streamer::server::run, &s));
00109
00110 ros::spin();
00111
00112
00113 s.stop();
00114 t.join();
00115
00116 }
00117 catch (std::exception& e)
00118 {
00119 std::cerr << "exception: " << e.what() << "\n";
00120 }
00121
00122 return 0;
00123 }
00124