mirror of
https://github.com/wjwwood/serial.git
synced 2026-01-22 19:54:57 +08:00
Simple sync read working.
This commit is contained in:
parent
ab455881b2
commit
7587b16fd0
30
serial/CMakeLists.txt
Normal file
30
serial/CMakeLists.txt
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
cmake_minimum_required(VERSION 2.4.6)
|
||||||
|
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
|
||||||
|
|
||||||
|
# Set the build type. Options are:
|
||||||
|
# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage
|
||||||
|
# Debug : w/ debug symbols, w/o optimization
|
||||||
|
# Release : w/o debug symbols, w/ optimization
|
||||||
|
# RelWithDebInfo : w/ debug symbols, w/ optimization
|
||||||
|
# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries
|
||||||
|
#set(ROS_BUILD_TYPE RelWithDebInfo)
|
||||||
|
|
||||||
|
rosbuild_init()
|
||||||
|
|
||||||
|
#set the default path for built executables to the "bin" directory
|
||||||
|
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
|
||||||
|
#set the default path for built libraries to the "lib" directory
|
||||||
|
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
|
||||||
|
|
||||||
|
#uncomment if you have defined messages
|
||||||
|
#rosbuild_genmsg()
|
||||||
|
#uncomment if you have defined services
|
||||||
|
#rosbuild_gensrv()
|
||||||
|
|
||||||
|
#common commands for building c++ executables and libraries
|
||||||
|
rosbuild_add_library(${PROJECT_NAME} src/serial.cpp)
|
||||||
|
#target_link_libraries(${PROJECT_NAME} another_library)
|
||||||
|
rosbuild_add_boost_directories()
|
||||||
|
rosbuild_link_boost(${PROJECT_NAME} system filesystem thread)
|
||||||
|
rosbuild_add_executable(test_serial src/test_serial.cpp)
|
||||||
|
target_link_libraries(test_serial serial)
|
||||||
1
serial/Makefile
Normal file
1
serial/Makefile
Normal file
@ -0,0 +1 @@
|
|||||||
|
include $(shell rospack find mk)/cmake.mk
|
||||||
167
serial/include/serial.h
Normal file
167
serial/include/serial.h
Normal file
@ -0,0 +1,167 @@
|
|||||||
|
/**
|
||||||
|
* @file serial.h
|
||||||
|
* @author William Woodall <wjwwood@gmail.com>
|
||||||
|
* @version 0.1
|
||||||
|
*
|
||||||
|
* @section LICENSE
|
||||||
|
*
|
||||||
|
* The MIT License
|
||||||
|
*
|
||||||
|
* Copyright (c) 2011 William Woodall
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
* of this software and associated documentation files (the "Software"), to deal
|
||||||
|
* in the Software without restriction, including without limitation the rights
|
||||||
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
* copies of the Software, and to permit persons to whom the Software is
|
||||||
|
* furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
* THE SOFTWARE.
|
||||||
|
*
|
||||||
|
* @section DESCRIPTION
|
||||||
|
*
|
||||||
|
* This provides a cross platform interface for interacting with Serial Ports.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef SERIAL_H
|
||||||
|
#define SERIAL_H
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include <boost/asio.hpp>
|
||||||
|
#include <boost/asio/serial_port.hpp>
|
||||||
|
#include <boost/bind.hpp>
|
||||||
|
#include <boost/thread.hpp>
|
||||||
|
|
||||||
|
#define READ_BUFFER_SIZE 4
|
||||||
|
#define SERIAL_BUFFER_SIZE 1024
|
||||||
|
|
||||||
|
class Serial {
|
||||||
|
public:
|
||||||
|
/** Constructor, creates a SerialPortBoost object without opening a port. */
|
||||||
|
Serial();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Constructor, creates a SerialPortBoost object and opens the port.
|
||||||
|
*
|
||||||
|
* @param port A std::string containing the address of the serial port,
|
||||||
|
* which would be something like 'COM1' on Windows and '/dev/ttyS0'
|
||||||
|
* on Linux.
|
||||||
|
*
|
||||||
|
* @param baudrate An integer that represents the buadrate
|
||||||
|
*
|
||||||
|
* @param timeout A double that represents the time (in seconds) until a
|
||||||
|
* timeout on reads occur. Setting this to a negative number will
|
||||||
|
* silently disable the timeout on reads.
|
||||||
|
*/
|
||||||
|
Serial(std::string port, int baudrate = 9600, double timeout = -1.0);
|
||||||
|
// Serial(string port, int baudrate = 9600, int bytesize = EIGHTBITS, int parity = PARITY_NONE, int stopbits = STOPBITS_ONE, double timeout = -1.0, bool xonxoff = false, bool rtscts = false, double writeTimeout = -1.0, bool dsrdtr = false, double interCharTimeout = -1.0);
|
||||||
|
|
||||||
|
/** Destructor */
|
||||||
|
~Serial();
|
||||||
|
|
||||||
|
/** Opens the serial port as long as the portname is set and the port isn't alreay open. */
|
||||||
|
void open();
|
||||||
|
|
||||||
|
/** Closes the serial port and terminates threads. */
|
||||||
|
void close();
|
||||||
|
|
||||||
|
/** Read size bytes from the serial port.
|
||||||
|
* If a timeout is set it may return less characters than requested. With no timeout
|
||||||
|
* it will block until the requested number of bytes have been read.
|
||||||
|
*
|
||||||
|
* @param buffer A char[] of length >= the size parameter to hold incoming data.
|
||||||
|
*
|
||||||
|
* @param size An integer defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* @return An integer representing the number of bytes read.
|
||||||
|
*/
|
||||||
|
int read(char* buffer, int size = 1);
|
||||||
|
|
||||||
|
/** Read size bytes from the serial port.
|
||||||
|
* If a timeout is set it may return less characters than requested. With no timeout
|
||||||
|
* it will block until the requested number of bytes have been read.
|
||||||
|
*
|
||||||
|
* @param size An integer defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* @return A std::string containing the data read.
|
||||||
|
*/
|
||||||
|
std::string read(int size=1);
|
||||||
|
|
||||||
|
/** Write length bytes from buffer to the serial port.
|
||||||
|
*
|
||||||
|
* @param data A char[] with data to be written to the serial port.
|
||||||
|
*
|
||||||
|
* @param length An integer representing the number of bytes to be written.
|
||||||
|
*
|
||||||
|
* @return An integer representing the number of bytes written.
|
||||||
|
*/
|
||||||
|
int write(char data[], int length);
|
||||||
|
|
||||||
|
/** Write a string to the serial port.
|
||||||
|
*
|
||||||
|
* @param data A std::string to be written to the serial port. (must be null terminated)
|
||||||
|
*
|
||||||
|
* @return An integer representing the number of bytes written to the serial port.
|
||||||
|
*/
|
||||||
|
int write(std::string data);
|
||||||
|
|
||||||
|
/** Checks the number of bytes waiting in the buffer.
|
||||||
|
*
|
||||||
|
* @return An integer representing the number of bytes in the serial buffer.
|
||||||
|
*/
|
||||||
|
int inWaiting();
|
||||||
|
|
||||||
|
/** Flushes the write buffer, blocks untill all data has been written. */
|
||||||
|
void flush();
|
||||||
|
|
||||||
|
/** Sets the logic level of the RTS line.
|
||||||
|
*
|
||||||
|
* @param level The logic level to set the RTS to. Defaults to true.
|
||||||
|
*/
|
||||||
|
void setRTS(bool level = true);
|
||||||
|
|
||||||
|
/** Sets the logic level of the DTR line.
|
||||||
|
*
|
||||||
|
* @param level The logic level to set the DTR to. Defaults to true.
|
||||||
|
*/
|
||||||
|
void setDTR(bool level = true);
|
||||||
|
|
||||||
|
/** Gets the status of the CTS line.
|
||||||
|
*
|
||||||
|
* @return A boolean value that represents the current logic level of the CTS line.
|
||||||
|
*/
|
||||||
|
bool getCTS();
|
||||||
|
|
||||||
|
/** Gets the status of the DSR line.
|
||||||
|
*
|
||||||
|
* @return A boolean value that represents the current logic level of the DSR line.
|
||||||
|
*/
|
||||||
|
bool getDSR();
|
||||||
|
private:
|
||||||
|
boost::asio::io_service io_service;
|
||||||
|
boost::asio::serial_port *serial_port;
|
||||||
|
|
||||||
|
boost::thread * io_service_thread;
|
||||||
|
|
||||||
|
char read_buffer[READ_BUFFER_SIZE];
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
std::string port;
|
||||||
|
int baudrate;
|
||||||
|
double timeout;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
||||||
26
serial/mainpage.dox
Normal file
26
serial/mainpage.dox
Normal file
@ -0,0 +1,26 @@
|
|||||||
|
/**
|
||||||
|
\mainpage
|
||||||
|
\htmlinclude manifest.html
|
||||||
|
|
||||||
|
\b boostserial is ...
|
||||||
|
|
||||||
|
<!--
|
||||||
|
Provide an overview of your package.
|
||||||
|
-->
|
||||||
|
|
||||||
|
|
||||||
|
\section codeapi Code API
|
||||||
|
|
||||||
|
<!--
|
||||||
|
Provide links to specific auto-generated API documentation within your
|
||||||
|
package that is of particular interest to a reader. Doxygen will
|
||||||
|
document pretty much every part of your code, so do your best here to
|
||||||
|
point the reader to the actual API.
|
||||||
|
|
||||||
|
If your codebase is fairly large or has different sets of APIs, you
|
||||||
|
should use the doxygen 'group' tag to keep these APIs together. For
|
||||||
|
example, the roscpp documentation has 'libros' group.
|
||||||
|
-->
|
||||||
|
|
||||||
|
|
||||||
|
*/
|
||||||
15
serial/manifest.xml
Normal file
15
serial/manifest.xml
Normal file
@ -0,0 +1,15 @@
|
|||||||
|
<package>
|
||||||
|
<description brief="serial">
|
||||||
|
|
||||||
|
serial
|
||||||
|
|
||||||
|
</description>
|
||||||
|
<author>William Woodall</author>
|
||||||
|
<license>BSD</license>
|
||||||
|
<review status="unreviewed" notes=""/>
|
||||||
|
<url>http://ros.org/wiki/serial</url>
|
||||||
|
<depend package="roscpp"/>
|
||||||
|
|
||||||
|
</package>
|
||||||
|
|
||||||
|
|
||||||
95
serial/src/serial.cpp
Normal file
95
serial/src/serial.cpp
Normal file
@ -0,0 +1,95 @@
|
|||||||
|
#include "serial.h"
|
||||||
|
|
||||||
|
Serial::Serial() {
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial::Serial(std::string port, int baudrate, double timeout) {
|
||||||
|
this->port = port;
|
||||||
|
this->baudrate = baudrate;
|
||||||
|
this->timeout = timeout;
|
||||||
|
this->open();
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial::~Serial() {
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::open() {
|
||||||
|
this->serial_port = new boost::asio::serial_port(this->io_service, this->port);
|
||||||
|
|
||||||
|
if(not serial_port->is_open()) {
|
||||||
|
std::cerr << "[AX2550] Failed to open serial port: " << this->port << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
try {
|
||||||
|
this->serial_port->set_option(boost::asio::serial_port_base::baud_rate(this->baudrate));
|
||||||
|
// this->serial_port->set_option(
|
||||||
|
// boost::asio::serial_port_base::flow_control(
|
||||||
|
// boost::asio::serial_port_base::flow_control::none));
|
||||||
|
// this->serial_port->set_option(
|
||||||
|
// boost::asio::serial_port_base::parity(
|
||||||
|
// boost::asio::serial_port_base::parity::even));
|
||||||
|
// this->serial_port->set_option(
|
||||||
|
// boost::asio::serial_port_base::stop_bits(
|
||||||
|
// boost::asio::serial_port_base::stop_bits::one));
|
||||||
|
// this->serial_port->set_option(boost::asio::serial_port_base::character_size(7));
|
||||||
|
} catch(std::exception &e) {
|
||||||
|
std::cerr << "[AX2550] Error opening serial port: " << e.what() << std::endl;
|
||||||
|
try {
|
||||||
|
if(this->serial_port->is_open())
|
||||||
|
this->serial_port->close();
|
||||||
|
} catch(std::exception &e) {
|
||||||
|
std::cerr << "[AX2550] Error closing serial port: " << e.what() << std::endl;
|
||||||
|
}
|
||||||
|
this->serial_port = NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::close() {
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
int Serial::read(char* buffer, int size) {
|
||||||
|
return this->serial_port->read_some(boost::asio::buffer(buffer, size));
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string Serial::read(int size) {
|
||||||
|
char serial_buffer[size];
|
||||||
|
int number_read = this->serial_port->read_some(boost::asio::buffer(serial_buffer, size));
|
||||||
|
serial_buffer[number_read] = NULL;
|
||||||
|
return std::string(serial_buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
int Serial::write(char data[], int length) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int Serial::write(std::string data) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int Serial::inWaiting() {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::flush() {
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::setRTS(bool level) {
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::setDTR(bool level) {
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getCTS() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getDSR() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
50
serial/src/test_serial.cpp
Normal file
50
serial/src/test_serial.cpp
Normal file
@ -0,0 +1,50 @@
|
|||||||
|
#include "ros/ros.h"
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "serial.h"
|
||||||
|
|
||||||
|
Serial *serial;
|
||||||
|
|
||||||
|
std::string toHex(std::string input) {
|
||||||
|
std::stringstream ss;
|
||||||
|
for(int i = 0; i != input.length(); i++) {
|
||||||
|
char temp[4];
|
||||||
|
sprintf(temp, "%.2X", input[i]);
|
||||||
|
ss << " ";
|
||||||
|
if(input[i] == 0x0A)
|
||||||
|
ss << "LF";
|
||||||
|
else if(input[i] == 0x0D)
|
||||||
|
ss << "NL";
|
||||||
|
else
|
||||||
|
ss << input[i];
|
||||||
|
ss << " " << std::hex << temp;
|
||||||
|
}
|
||||||
|
return ss.str();
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
ros::init(argc, argv, "serial_test_node");
|
||||||
|
|
||||||
|
ros::NodeHandle n;
|
||||||
|
|
||||||
|
std::string port("/dev/tty.usbserial-A900cfJA");
|
||||||
|
|
||||||
|
serial = new Serial(port);
|
||||||
|
|
||||||
|
ros::Rate loop_rate(10);
|
||||||
|
|
||||||
|
while (ros::ok()) {
|
||||||
|
std::string result = serial->read(1);
|
||||||
|
|
||||||
|
ROS_INFO("%d,%s", result.length(), toHex(result).c_str());
|
||||||
|
|
||||||
|
ros::spinOnce();
|
||||||
|
|
||||||
|
loop_rate.sleep();
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
Loading…
x
Reference in New Issue
Block a user