34 #include <boost/asio.hpp> 35 #include <boost/bind.hpp> 36 #include <boost/thread.hpp> 43 int main(
int argc,
char* argv[])
45 ros::init(argc, argv,
"rosserial_server_serial_node");
49 ros::param::param<std::string>(
"~port", port,
"/dev/ttyACM0");
50 ros::param::param<int>(
"~baud", baud, 57600);
52 boost::asio::io_service io_service;
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char *argv[])
Single, reconnecting class for a serial rosserial session.