00001 00034 #include <boost/asio.hpp> 00035 #include <boost/bind.hpp> 00036 #include <boost/thread.hpp> 00037 00038 #include <ros/ros.h> 00039 00040 #include "rosserial_server/session.h" 00041 #include "rosserial_server/tcp_server.h" 00042 00043 int main(int argc, char* argv[]) 00044 { 00045 // Initialize ROS. 00046 ros::init(argc, argv, "rosserial_server_socket_node"); 00047 int port; 00048 ros::param::param<int>("~port", port, 11411); 00049 00050 // Listen for rosserial TCP connections in background thread. 00051 boost::asio::io_service io_service; 00052 rosserial_server::TcpServer< 00053 rosserial_server::Session<boost::asio::ip::tcp::socket> > s(io_service, port); 00054 boost::thread(boost::bind(&boost::asio::io_service::run, &io_service)); 00055 ROS_INFO_STREAM("Listening on port " << port); 00056 00057 ros::spin(); 00058 return 0; 00059 }