34 #include <boost/asio.hpp> 35 #include <boost/bind.hpp> 36 #include <boost/thread.hpp> 42 using boost::asio::ip::udp;
43 using boost::asio::ip::address;
46 int main(
int argc,
char* argv[])
48 ros::init(argc, argv,
"rosserial_server_udp_socket_node");
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");
57 boost::asio::io_service io_service;
60 udp::endpoint(udp::v4(), server_port),
61 udp::endpoint(address::from_string(client_addr), client_port));
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[])