udp_socket_node.cpp
Go to the documentation of this file.
1 
34 #include <boost/asio.hpp>
35 #include <boost/bind.hpp>
36 #include <boost/thread.hpp>
37 
38 #include <ros/ros.h>
39 
41 
42 using boost::asio::ip::udp;
43 using boost::asio::ip::address;
44 
45 
46 int main(int argc, char* argv[])
47 {
48  ros::init(argc, argv, "rosserial_server_udp_socket_node");
49 
50  int server_port;
51  int client_port;
52  std::string client_addr;
53  ros::param::param<int>("~server_port", server_port, 11411);
54  ros::param::param<int>("~client_port", client_port, 11411);
55  ros::param::param<std::string>("~client_addr", client_addr, "127.0.0.1");
56 
57  boost::asio::io_service io_service;
58  rosserial_server::UdpSocketSession udp_socket_session(
59  io_service,
60  udp::endpoint(udp::v4(), server_port),
61  udp::endpoint(address::from_string(client_addr), client_port));
62  io_service.run();
63 
64  return 0;
65 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Reconnecting class for a UDP rosserial session.
int main(int argc, char *argv[])


rosserial_server
Author(s): Mike Purvis
autogenerated on Mon Jun 10 2019 14:53:36