serial.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (C) 2015, Jack O'Quin
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of the author nor of other contributors may be
00018 #    used to endorse or promote products derived from this software
00019 #    without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 """
00035 This module handles serial messages from the Arduino Mega 2560 mounted
00036 on the version 2 BWI segbots.
00037 """
00038 
00039 # enable some python3 compatibility options:
00040 from __future__ import absolute_import, print_function, unicode_literals
00041 
00042 import io
00043 import rospy
00044 import select
00045 import serial
00046 
00047 
00048 class ArduinoDevice(object):
00049     """ Class for managing the Arduino serial port connection.
00050     """
00051     def __init__(self, port='/dev/ttyACM0', baud=115200):
00052         self.port = port
00053         """ Path name for Arduino serial port. """
00054         self.baud = baud
00055         """ Baud rate for Arduino serial port. """
00056         self.dev = None
00057         """ Arduino serial device connection. """
00058 
00059     def close(self):
00060         if self.dev:
00061             self.dev.close()
00062         self.dev = None
00063 
00064     def ok(self):
00065         """ :returns: ``True`` if Arduino contacted. """
00066         return self.dev is not None
00067 
00068     def open(self):
00069         """ Open the Arduino serial device interface.
00070 
00071         :returns: ``True`` if open succeeds.
00072         """
00073         try:
00074             self.dev = serial.Serial(self.port, self.baud)
00075         except IOError as e:
00076             # HACK: serial does not return errno.ENOTTY as it should,
00077             #       so check the exact string.
00078             enotty = ("Could not configure port: " +
00079                       "(25, 'Inappropriate ioctl for device')")
00080             if str(e) != enotty:        # is it a serial port?
00081                 rospy.logerr('Serial port open failed at ' +
00082                              str(self.baud) + ' baud: ' + str(e))
00083                 return False
00084         else:
00085             rospy.loginfo('Serial port ' + self.port + ' opened at ' +
00086                           str(self.baud) + ' baud.')
00087             self.dev.flushInput()       # discard any old data
00088             return True
00089 
00090         # Not a serial port: see if it's a regular file with test data.
00091         try:
00092             self.dev = io.open(self.port, 'rb')
00093         except IOError as e:
00094             rospy.logerr('File open failed: ' + str(e))
00095             return False
00096         else:
00097             rospy.logdebug('Test file opened: ' + self.port)
00098             return True
00099 
00100     def read(self):
00101         """ Read a line from the serial port.
00102 
00103         :returns: a string containing the next line, maybe empty.
00104         """
00105         serial_msg = ''
00106         try:
00107             serial_msg = self.dev.readline()
00108         except serial.SerialException as e:
00109             rospy.logerr('Serial port ' + self.port +
00110                          ' read failed: ' + str(e))
00111             self.close()
00112         except (select.error, OSError) as e:
00113             errno_, perror = e.args
00114             rospy.logwarn('Serial port read error: ' + str(perror))
00115             self.close()
00116         else:
00117             # Sometimes the Arduino sends out-of-range characters on
00118             # start-up. Just ignore them.
00119             serial_msg = serial_msg.decode('ascii', 'ignore')
00120             rospy.logdebug('Arduino message: ' + serial_msg)
00121             if serial_msg == '':        # end of test data file?
00122                 self.close()            # test ended
00123             return serial_msg
00124         return ''                       # no data read


segbot_sensors
Author(s): Piyush Khandelwal
autogenerated on Thu Jun 6 2019 21:37:13