|
@@ -37,13 +37,19 @@ class Arduino:
|
|
|
N_ANALOG_PORTS = 10
|
|
|
N_DIGITAL_PORTS = 54
|
|
|
|
|
|
- def __init__(self, port="/dev/ttyAMA0", baudrate=57600, timeout=0.5):
|
|
|
+ def __init__(self, is_use_serial, serial_port="/dev/ttyACM0", baudrate=57600, i2c_slave_addr=8, timeout=0.5):
|
|
|
self.PID_RATE = 40 # Do not change this! It is a fixed property of the Arduino PID controller.
|
|
|
self.PID_INTERVAL = 25
|
|
|
|
|
|
- self.port = port
|
|
|
+ self.is_use_serial = is_use_serial
|
|
|
+ self.serial_port = serial_port
|
|
|
self.baudrate = baudrate
|
|
|
+
|
|
|
+ self.i2c_bus = smbus.SMBus(1)
|
|
|
+ self.i2c_slave_addr = i2c_slave_addr
|
|
|
+
|
|
|
self.timeout = timeout
|
|
|
+
|
|
|
self.encoder_count = 0
|
|
|
self.writeTimeout = timeout
|
|
|
self.interCharTimeout = timeout/30.
|
|
@@ -58,9 +64,15 @@ class Arduino:
|
|
|
self.digital_sensor_cache = [None] * self.N_DIGITAL_PORTS
|
|
|
|
|
|
def connect(self):
|
|
|
+ if self.is_use_serial:
|
|
|
+ self.serial_connect()
|
|
|
+ else:
|
|
|
+ self.i2c_connect()
|
|
|
+
|
|
|
+ def serial_connect(self):
|
|
|
try:
|
|
|
- print "Connecting to Arduino on port", self.port, "..."
|
|
|
- self.port = Serial(port=self.port, baudrate=self.baudrate, timeout=self.timeout, writeTimeout=self.writeTimeout)
|
|
|
+ print "Connecting to Arduino on port", self.serial_port, "..."
|
|
|
+ self.serial_port = Serial(port=self.serial_port, baudrate=self.baudrate, timeout=self.timeout, writeTimeout=self.writeTimeout)
|
|
|
# The next line is necessary to give the firmware time to wake up.
|
|
|
time.sleep(1)
|
|
|
test = self.get_baud()
|
|
@@ -73,7 +85,7 @@ class Arduino:
|
|
|
|
|
|
self.beep_ring(1)
|
|
|
print "Connected at", self.baudrate
|
|
|
- print "Arduino is ready."
|
|
|
+ print "Arduino is ready !"
|
|
|
except SerialException:
|
|
|
print "Serial Exception:"
|
|
|
print sys.exc_info()
|
|
@@ -82,22 +94,46 @@ class Arduino:
|
|
|
print "Cannot connect to Arduino!"
|
|
|
os._exit(1)
|
|
|
|
|
|
+ def i2c_connect(self):
|
|
|
+ try:
|
|
|
+
|
|
|
+ print "Connecting to Arduino on IIC addr ", self.i2c_slave_addr, "..."
|
|
|
+ test = self.i2c_get_baud()
|
|
|
+ if test != self.baudrate:
|
|
|
+ time.sleep(1)
|
|
|
+ print "Connecting ..."
|
|
|
+ test = self.i2c_get_baud()
|
|
|
+ if test != self.baudrate:
|
|
|
+ raise Exception
|
|
|
+
|
|
|
+ self.beep_ring(1)
|
|
|
+ print "Connected at", self.baudrate
|
|
|
+ print "Arduino is ready !"
|
|
|
+ except Exception:
|
|
|
+ print sys.exc_info()
|
|
|
+ print "Traceback follows:"
|
|
|
+ traceback.print_exc(file=sys.stdout)
|
|
|
+ print "Cannot connect to Arduino IIC slave addr !"
|
|
|
+ os._exit(1)
|
|
|
+
|
|
|
+
|
|
|
def open(self):
|
|
|
''' Open the serial port.
|
|
|
'''
|
|
|
- self.port.open()
|
|
|
+ self.serial_port.open()
|
|
|
|
|
|
def close(self):
|
|
|
''' Close the serial port.
|
|
|
'''
|
|
|
self.beep_ring(0)
|
|
|
- self.port.close()
|
|
|
+ self.serial_port.close()
|
|
|
+ self.i2c_bus.close()
|
|
|
|
|
|
def send(self, cmd):
|
|
|
''' This command should not be used on its own: it is called by the execute commands
|
|
|
below in a thread safe manner.
|
|
|
'''
|
|
|
- self.port.write(cmd + '\r')
|
|
|
+ self.serial_port.write(cmd + '\r')
|
|
|
|
|
|
def recv(self, timeout=0.5):
|
|
|
timeout = min(timeout, self.timeout)
|
|
@@ -109,7 +145,7 @@ class Arduino:
|
|
|
value = ''
|
|
|
attempts = 0
|
|
|
while c != '\r':
|
|
|
- c = self.port.read(1)
|
|
|
+ c = self.serial_port.read(1)
|
|
|
value += c
|
|
|
attempts += 1
|
|
|
if attempts * self.interCharTimeout > timeout:
|
|
@@ -151,7 +187,7 @@ class Arduino:
|
|
|
self.mutex.acquire()
|
|
|
|
|
|
try:
|
|
|
- self.port.flushInput()
|
|
|
+ self.serial_port.flushInput()
|
|
|
except:
|
|
|
pass
|
|
|
|
|
@@ -159,12 +195,12 @@ class Arduino:
|
|
|
attempts = 0
|
|
|
|
|
|
try:
|
|
|
- self.port.write(cmd + '\r')
|
|
|
+ self.serial_port.write(cmd + '\r')
|
|
|
value = self.recv(self.timeout)
|
|
|
while attempts < ntries and (value == '' or value == 'Invalid Command' or value == None):
|
|
|
try:
|
|
|
- self.port.flushInput()
|
|
|
- self.port.write(cmd + '\r')
|
|
|
+ self.serial_port.flushInput()
|
|
|
+ self.serial_port.write(cmd + '\r')
|
|
|
value = self.recv(self.timeout)
|
|
|
except:
|
|
|
print "Exception executing command: " + cmd
|
|
@@ -182,19 +218,19 @@ class Arduino:
|
|
|
'''
|
|
|
self.mutex.acquire()
|
|
|
try:
|
|
|
- self.port.flushInput()
|
|
|
+ self.serial_port.flushInput()
|
|
|
except:
|
|
|
pass
|
|
|
|
|
|
ntries = 1
|
|
|
attempts = 0
|
|
|
try:
|
|
|
- self.port.write(cmd + '\r')
|
|
|
+ self.serial_port.write(cmd + '\r')
|
|
|
values = self.recv_array()
|
|
|
while attempts < ntries and (values == '' or values == 'Invalid Command' or values == [] or values == None):
|
|
|
try:
|
|
|
- self.port.flushInput()
|
|
|
- self.port.write(cmd + '\r')
|
|
|
+ self.serial_port.flushInput()
|
|
|
+ self.serial_port.write(cmd + '\r')
|
|
|
values = self.recv_array()
|
|
|
except:
|
|
|
print("Exception executing command: " + cmd)
|
|
@@ -219,7 +255,7 @@ class Arduino:
|
|
|
self.mutex.acquire()
|
|
|
|
|
|
try:
|
|
|
- self.port.flushInput()
|
|
|
+ self.serial_port.flushInput()
|
|
|
except:
|
|
|
pass
|
|
|
|
|
@@ -227,12 +263,12 @@ class Arduino:
|
|
|
attempts = 0
|
|
|
|
|
|
try:
|
|
|
- self.port.write(cmd + '\r')
|
|
|
+ self.serial_port.write(cmd + '\r')
|
|
|
ack = self.recv(self.timeout)
|
|
|
while attempts < ntries and (ack == '' or ack == 'Invalid Command' or ack == None):
|
|
|
try:
|
|
|
- self.port.flushInput()
|
|
|
- self.port.write(cmd + '\r')
|
|
|
+ self.serial_port.flushInput()
|
|
|
+ self.serial_port.write(cmd + '\r')
|
|
|
ack = self.recv(self.timeout)
|
|
|
except:
|
|
|
print "Exception executing command: " + cmd
|
|
@@ -255,6 +291,11 @@ class Arduino:
|
|
|
cmd = 'u '+str(AWheel_Kp)+':'+str(AWheel_Kd)+':'+str(AWheel_Ki)+':'+str(AWheel_Ko)+':'+str(BWheel_Kp)+':'+str(BWheel_Kd)+':'+str(BWheel_Ki)+':'+str(BWheel_Ko)+':'+str(CWheel_Kp)+':'+str(CWheel_Kd)+':'+str(CWheel_Ki)+':'+str(CWheel_Ko)
|
|
|
self.execute_ack(cmd)
|
|
|
|
|
|
+ def i2c_update_pid(self, AWheel_Kp, AWheel_Kd, AWheel_Ki, AWheel_Ko,
|
|
|
+ BWheel_Kp, BWheel_Kd, BWheel_Ki, BWheel_Ko,
|
|
|
+ CWheel_Kp, CWheel_Kd, CWheel_Ki, CWheel_Ko ):
|
|
|
+ print "Updating PID parameters by IIC"
|
|
|
+
|
|
|
def get_baud(self):
|
|
|
''' Get the current baud rate on the serial port.
|
|
|
'''
|
|
@@ -263,6 +304,21 @@ class Arduino:
|
|
|
except:
|
|
|
return None
|
|
|
|
|
|
+ def i2c_get_baud(self):
|
|
|
+ ''' Get the current baud rate on the arduino IIC addr.
|
|
|
+ '''
|
|
|
+ try:
|
|
|
+ self.i2c_bus.write_byte(self.i2c_addr, ord('b'))
|
|
|
+ self.i2c_bus.write_byte(self.i2c_addr, ord('\r'))
|
|
|
+ time.sleep(0.1)
|
|
|
+ values = self.i2c_bus.read_i2c_block_data(self.i2c_addr, 0, 5)
|
|
|
+ values = map(chr, values)
|
|
|
+ ret = ''.join(values)
|
|
|
+ #print "ret:"+ret
|
|
|
+ return int(ret)
|
|
|
+ except:
|
|
|
+ return None
|
|
|
+
|
|
|
def get_encoder_counts(self):
|
|
|
values = self.execute_array('e')
|
|
|
if len(values) != 3:
|
|
@@ -272,16 +328,44 @@ class Arduino:
|
|
|
else:
|
|
|
return values
|
|
|
|
|
|
+ def i2c_get_encoder_counts(self):
|
|
|
+ #values = self.execute_array('e')
|
|
|
+ #if len(values) != 3:
|
|
|
+ # print "Encoder count was not 3"
|
|
|
+ # raise SerialException
|
|
|
+ # return None
|
|
|
+ #else:
|
|
|
+ # return values
|
|
|
+
|
|
|
def reset_encoders(self):
|
|
|
- ''' Reset the encoder counts to 0
|
|
|
+ ''' Reset the encoder counts to 0 by serial port
|
|
|
'''
|
|
|
return self.execute_ack('r')
|
|
|
|
|
|
+ def i2c_reset_encoders(self):
|
|
|
+ ''' Reset the encoder counts to 0 by IIC
|
|
|
+ '''
|
|
|
+ try:
|
|
|
+ self.i2c_bus.write_byte(self.i2c_addr, ord('r'))
|
|
|
+ self.i2c_bus.write_byte(self.i2c_addr, ord('\r'))
|
|
|
+ except:
|
|
|
+ return None
|
|
|
+
|
|
|
def drive(self, AWheel, BWheel, CWheel):
|
|
|
''' Speeds are given in encoder ticks per PID interval
|
|
|
'''
|
|
|
#rospy.loginfo("drive() A:" + str(AWheel) + ",B:" + str(BWheel) + ",C:" + str(CWheel))
|
|
|
return self.execute_ack('m %d %d %d' %(AWheel, BWheel, CWheel))
|
|
|
+
|
|
|
+ def i2c_drive(self, AWheel, BWheel, CWheel):
|
|
|
+ ''' Speeds are given in encoder ticks per PID interval
|
|
|
+ '''
|
|
|
+ #rospy.loginfo("drive() A:" + str(AWheel) + ",B:" + str(BWheel) + ",C:" + str(CWheel))
|
|
|
+ cmd = (' %d %d %d\r' %(AWheel, BWheel, CWheel))
|
|
|
+ try:
|
|
|
+ self.i2c_bus.write_i2c_block_data(self.i2c_addr, ord('m'), [ord(c) for c in cmd])
|
|
|
+ except:
|
|
|
+ return None
|
|
|
|
|
|
def drive_m_per_s(self, AWheel, BWheel, CWheel):
|
|
|
''' Set the motor speeds in meters per second.
|
|
@@ -301,6 +385,13 @@ class Arduino:
|
|
|
'''
|
|
|
self.drive(0, 0, 0)
|
|
|
|
|
|
+ def i2c_stop(self):
|
|
|
+ cmd = (' 0 0 0\r')
|
|
|
+ try:
|
|
|
+ self.i2c_bus.write_i2c_block_data(self.i2c_addr, ord('m'), [ord(c) for c in cmd])
|
|
|
+ except:
|
|
|
+ return None
|
|
|
+
|
|
|
def analog_read(self, pin):
|
|
|
return self.execute('a %d' %pin)
|
|
|
|
|
@@ -340,6 +431,15 @@ class Arduino:
|
|
|
else:
|
|
|
return values
|
|
|
|
|
|
+ def i2c_get_pidin(self):
|
|
|
+ #values = self.execute_array('i')
|
|
|
+ #if len(values) != 3:
|
|
|
+ # print "pidin was not 3"
|
|
|
+ # raise SerialException
|
|
|
+ # return None
|
|
|
+ #else:
|
|
|
+ # return values
|
|
|
+
|
|
|
def get_pidout(self):
|
|
|
values = self.execute_array('o')
|
|
|
if len(values) != 3:
|
|
@@ -349,14 +449,18 @@ class Arduino:
|
|
|
else:
|
|
|
return values
|
|
|
|
|
|
+ def i2c_get_pidout(self):
|
|
|
+ #values = self.execute_array('o')
|
|
|
+ #if len(values) != 3:
|
|
|
+ # print "pidout was not 3"
|
|
|
+ # raise SerialException
|
|
|
+ # return None
|
|
|
+ #else:
|
|
|
+ # return values
|
|
|
|
|
|
""" Basic test for connectivity """
|
|
|
if __name__ == "__main__":
|
|
|
- if os.name == "posix":
|
|
|
- portName = "/dev/ttyACM0"
|
|
|
- else:
|
|
|
- portName = "COM43" # Windows style COM port.
|
|
|
-
|
|
|
+ portName = "/dev/ttyACM0"
|
|
|
baudRate = 57600
|
|
|
|
|
|
myArduino = Arduino(port=portName, baudrate=baudRate, timeout=0.5)
|