Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 """
00035 This module handles serial messages from the Arduino Mega 2560 mounted
00036 on the version 2 BWI segbots.
00037 """
00038
00039
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
00077
00078 enotty = ("Could not configure port: "
00079 + "(25, 'Inappropriate ioctl for device')")
00080 if str(e) != enotty:
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()
00088 return True
00089
00090
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
00118
00119 serial_msg = serial_msg.decode('ascii', 'ignore')
00120 rospy.logdebug('Arduino message: ' + serial_msg)
00121 if serial_msg == '':
00122 self.close()
00123 return serial_msg
00124 return ''