serial_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/serial_session.h"
00041 
00042 int main(int argc, char* argv[])
00043 {
00044   // Initialize ROS.
00045   ros::init(argc, argv, "rosserial_server_serial_node");
00046   std::string port;
00047   ros::param::param<std::string>("~port", port, "/dev/ttyACM0");
00048   int baud;
00049   ros::param::param<int>("~baud", baud, 57600);
00050 
00051   // Run boost::asio io service in a background thread.
00052   boost::asio::io_service io_service;
00053   new rosserial_server::SerialSession(io_service, port, baud);
00054   boost::thread(boost::bind(&boost::asio::io_service::run, &io_service));
00055 
00056   ros::spin();
00057   return 0;
00058 }


rosserial_server
Author(s): Mike Purvis
autogenerated on Thu Jun 6 2019 19:56:34