Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #include <telekyb_serial/ThreadedSerialDevice.hpp>
00009
00010 #include <iostream>
00011
00012 #include <ros/ros.h>
00013
00014 using namespace telekyb;
00015
00016 class SerialListener : public SerialDeviceListener
00017 {
00018 void handleReadSerialData(const std::vector<char>& data) {
00019 std::string msg(&data[0], data.size());
00020 ROS_INFO_STREAM("Received CB with: " << msg);
00021 }
00022 };
00023
00024 int main(int argc, char **argv) {
00025
00026 ros::init(argc,argv,"test_threadedserial");
00027
00028 SerialListener listener;
00029
00030 #ifdef __APPLE__
00031 ThreadedSerialDevice d("/dev/tty.usbserial-A600eG5l");
00032 #else
00033 ThreadedSerialDevice d("/dev/serial/by-id/usb-FTDI_FT232R_USB_UART_A600eG5l-if00-port0", "\r\n", true, O_RDWR | O_NOCTTY | O_NONBLOCK);
00034 #endif
00035
00036
00037
00038
00039
00040 tcflag_t cflag = CS8 | CLOCAL | CREAD;
00041
00042 d.setTermiosAttrCFlag(cflag);
00043 d.setTermiosAttrSpeed(B115200,B115200);
00044
00045 d.registerSerialDeviceListener(&listener);
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060 ros::waitForShutdown();
00061
00062 return 0;
00063 }
00064
00065