topic_streamer.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  * main.cpp
00030  *
00031  *  Created on: Nov 1, 2012
00032  *      Author: jkammerl
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   // Default server configuration
00066   ros_http_video_streamer::ServerConfiguration server_conf;
00067 
00068   // ROS parameters
00069   ros::NodeHandle priv_nh_("~");
00070 
00071   // read network port from param server
00072   priv_nh_.param<int>("port", server_conf.port_, server_conf.port_);
00073 
00074   // read default codec from param server
00075   priv_nh_.param<std::string>("codec", server_conf.codec_, server_conf.codec_);
00076 
00077   // read default bitrate from param server
00078   priv_nh_.param<int>("bitrate", server_conf.bitrate_, server_conf.bitrate_);
00079 
00080   // read default frame rate from param server
00081   priv_nh_.param<int>("framerate", server_conf.framerate_, server_conf.framerate_);
00082 
00083   // read quality parameter from param server
00084   priv_nh_.param<int>("quality", server_conf.quality_, server_conf.quality_);
00085 
00086   // read group of pictures from param server
00087   priv_nh_.param<int>("gop", server_conf.gop_, server_conf.gop_);
00088 
00089   // read default encoding profile from param server
00090   priv_nh_.param<std::string>("profile", server_conf.profile_, server_conf.profile_);
00091 
00092   // read default encoding profile from param server
00093   priv_nh_.param<std::string>("wwwroot", server_conf.wwwroot_, server_conf.wwwroot_);
00094 
00095   // read default ROS transport scheme
00096   priv_nh_.param<std::string>("transport", server_conf.ros_transport_, server_conf.ros_transport_);
00097 
00098   // read default encoding profile from param server
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     // Run server in background thread.
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     // Stop the server.
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 


ros_web_video
Author(s): Julius Kammer
autogenerated on Thu Jun 6 2019 21:07:01