udp_socket_node.cpp
Go to the documentation of this file.
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/udp_socket_session.h"
00041 
00042 using boost::asio::ip::udp;
00043 using boost::asio::ip::address;
00044 
00045 
00046 int main(int argc, char* argv[])
00047 {
00048   ros::init(argc, argv, "rosserial_server_udp_socket_node");
00049 
00050   int server_port;
00051   int client_port;
00052   std::string client_addr;
00053   ros::param::param<int>("~server_port", server_port, 11411);
00054   ros::param::param<int>("~client_port", client_port, 11411);
00055   ros::param::param<std::string>("~client_addr", client_addr, "127.0.0.1");
00056 
00057   boost::asio::io_service io_service;
00058   rosserial_server::UdpSocketSession udp_socket_session(
00059       io_service,
00060       udp::endpoint(udp::v4(), server_port),
00061       udp::endpoint(address::from_string(client_addr), client_port));
00062   io_service.run();
00063 
00064   return 0;
00065 }


rosserial_server
Author(s): Mike Purvis
autogenerated on Sat Oct 7 2017 03:08:51