$search
00001 """ 00002 A Python library for the Robotics Connection SerializerTM micro controller. 00003 Created for The Pi Robot Project: http://www.pirobot.org 00004 Copyright (c) 2010 Patrick Goebel. All rights reserved. 00005 00006 This program is free software; you can redistribute it and/or modify 00007 it under the terms of the GNU General Public License as published by 00008 the Free Software Foundation; either version 2 of the License, or 00009 (at your option) any later version. 00010 00011 This program is distributed in the hope that it will be useful, 00012 but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 GNU General Public License for more details at: 00015 00016 http://www.gnu.org/licenses/gpl.html 00017 00018 NOTE: See the offical SerializerTM manual at: 00019 http://www.roboticsconnection.com/multimedia/docs/Serializer_3.0_UserGuide.pdf 00020 00021 Basic Usage: 00022 00023 mySerializer = Serializer(port="/dev/ttyUSB0", baudrate=19200, timeout=0.05) 00024 mySerializer.connect() 00025 myPing = Ping(mySerializer, 4) 00026 myIR = GP2D12(mySerializer, 4) 00027 00028 print myPing.value() 00029 print myIR.value() 00030 00031 mySerializer.stop() 00032 mySerializer.close() 00033 00034 See the example files for more details. 00035 """ 00036 00037 import threading 00038 import math 00039 import os 00040 import time 00041 import sys 00042 from serial.serialutil import SerialException 00043 from enhancedserial import EnhancedSerial 00044 00045 class Serializer(): 00046 ''' Configuration Parameters 00047 ''' 00048 N_ANALOG_PORTS = 6 00049 N_DIGITAL_PORTS = 12 00050 00051 MILLISECONDS_PER_PID_LOOP = 1.6 # Do not change this! It is a fixed property of the Serializer PID controller. 00052 00053 default_pid_params = dict() 00054 pi_robot = False # Special flag set True when using Pi Robot 00055 if pi_robot: 00056 default_pid_params['units'] = 0 # 1 is inches, 0 is metric (cm for sensors, meters for wheels measurements) and 2 is "raw" 00057 default_pid_params['wheel_diameter'] = 0.132 # meters (5.0 inches) meters or inches depending on UNITS 00058 default_pid_params['wheel_track'] = 0.3365 # meters (12.8 inches) meters or inches units depending on UNITS 00059 default_pid_params['encoder_resolution'] = 624 # encoder ticks per revolution of the wheel without external gears 00060 default_pid_params['gear_reduction'] = 1.667 # This is for external gearing if you have any. In this case there is a 60/36 tooth gear ratio. 00061 00062 default_pid_params['encoder_type'] = 1 # 1 = quadrature, 0 = single 00063 default_pid_params['motors_reversed'] = True # Multiplies encoder counts by -1 if the motor rotation direction is reversed. 00064 00065 default_pid_params['init_pid'] = False # Set to True if you want to update UNITS, VPID and DPID parameters. Otherwise, those stored in the Serializer's firmware are used.** 00066 00067 default_pid_params['VPID_P'] = 2 # Proportional 00068 default_pid_params['VPID_I'] = 0 # Integral 00069 default_pid_params['VPID_D'] = 5 # Derivative 00070 default_pid_params['VPID_L'] = 45 # Loop: this together with UNITS and WHEEL_DIAMETER determines real-world velocity 00071 00072 default_pid_params['DPID_P'] = 1 # Proportional 00073 default_pid_params['DPID_I'] = 0 # Integral 00074 default_pid_params['DPID_D'] = 0 # Derivative 00075 default_pid_params['DPID_A'] = 5 # Acceleration 00076 default_pid_params['DPID_B'] = 10 # Dead band 00077 00078 BAD_VALUE = -999 00079 00080 def __init__(self, pid_params=default_pid_params, port="/dev/ttyUSB0", baudrate=19200, timeout=0.5): 00081 self.port = port 00082 self.baudrate = baudrate 00083 self.timeout = timeout 00084 self.use_base_controller = pid_params['use_base_controller'] 00085 00086 if self.use_base_controller: 00087 self.wheel_diameter = pid_params['wheel_diameter'] 00088 self.wheel_track = pid_params['wheel_track'] 00089 self.encoder_resolution = pid_params['encoder_resolution'] 00090 self.encoder_type = pid_params['encoder_type'] 00091 self.gear_reduction = pid_params['gear_reduction'] 00092 self.motors_reversed = pid_params['motors_reversed'] 00093 00094 self.init_pid = pid_params['init_pid'] 00095 self.units = pid_params['units'] 00096 self.VPID_P = pid_params['VPID_P'] 00097 self.VPID_I = pid_params['VPID_I'] 00098 self.VPID_D = pid_params['VPID_D'] 00099 self.VPID_L = pid_params['VPID_L'] 00100 self.DPID_P = pid_params['DPID_P'] 00101 self.DPID_I = pid_params['DPID_I'] 00102 self.DPID_D = pid_params['DPID_D'] 00103 self.DPID_A = pid_params['DPID_A'] 00104 self.DPID_B = pid_params['DPID_B'] 00105 00106 self.loop_interval = None 00107 self.ticks_per_meter = None 00108 self.messageLock = threading.Lock() 00109 00110 ''' An array to cache analog sensor readings''' 00111 self.analog_sensor_cache = [None] * self.N_ANALOG_PORTS 00112 00113 ''' An array to cache digital sensor readings''' 00114 self.digital_sensor_cache = [None] * self.N_DIGITAL_PORTS 00115 00116 def connect(self): 00117 try: 00118 print "Connecting to Serializer on port", self.port, "..." 00119 self.port = EnhancedSerial(port=self.port, baudrate=self.baudrate, timeout=self.timeout, writeTimeout=self.timeout) 00120 time.sleep(1) 00121 self.port.write('cfg baud\r') 00122 test = (self.port.readline(eol='>')[0:-3]).strip() 00123 if test != str(self.baudrate): 00124 time.sleep(1) 00125 self.port.write('cfg baud\r') 00126 test = (self.port.readline(eol='>')[0:-3]).strip() 00127 if test != str(self.baudrate): 00128 raise SerialException 00129 print "Connected at", self.baudrate, "baud. Current voltage:", self.voltage() 00130 print "Serializer is ready." 00131 00132 # Take care of the UNITS, VPID and DPID parameters for PID drive control. 00133 if self.init_pid: 00134 self.init_PID() 00135 else: 00136 self.units = self.get_units() 00137 [self.VPID_P, self.VPID_I, self.VPID_D, self.VPID_L] = self.get_vpid() 00138 [self.DPID_P, self.DPID_I, self.DPID_D, self.DPID_A, self.DPID_B] = self.get_dpid() 00139 00140 if self.use_base_controller: 00141 if self.units == 0: 00142 self.ticks_per_meter = int(self.encoder_resolution * self.gear_reduction / (self.wheel_diameter * math.pi)) 00143 elif self.units == 1: 00144 self.ticks_per_meter = int(self.encoder_resolution * self.gear_reduction / (self.wheel_diameter * math.pi * 2.54 / 100.0)) 00145 00146 self.loop_interval = self.VPID_L * self.MILLISECONDS_PER_PID_LOOP / 1000 00147 00148 00149 except SerialException: 00150 print "Cannot connect to Serializer!" 00151 print "Make sure you are plugged in and turned on." 00152 os._exit(1) 00153 00154 def init_PID(self): 00155 print "Updating Units and PID parameters." 00156 self.set_encoder(self.encoder_type) 00157 self.set_units(self.units) 00158 self.set_vpid(self.VPID_P, self.VPID_I, self.VPID_D, self.VPID_L) 00159 self.set_dpid(self.DPID_P, self.DPID_I, self.DPID_D, self.DPID_A, self.DPID_B) 00160 00161 def open(self): 00162 ''' Open the serial port. 00163 ''' 00164 with self.messageLock: 00165 self.port.open() 00166 00167 def close(self): 00168 ''' Close the serial port. 00169 ''' 00170 with self.messageLock: 00171 self.port.close() 00172 00173 def send(self, cmd): 00174 ''' This command should not be used on its own: it is called by the execute commands 00175 below in a thread safe manner. 00176 ''' 00177 self.port.write(cmd + '\r') 00178 00179 def recv(self): 00180 ''' This command should not be used on its own: it is called by the execute commands 00181 below in a thread safe manner. 00182 ''' 00183 value = (self.port.readline(eol='>')[0:-3]).strip() 00184 return value 00185 00186 def recv_ack(self): 00187 ''' This command should not be used on its own: it is called by the execute commands 00188 below in a thread safe manner. 00189 ''' 00190 ack = self.recv() 00191 return ack == 'ACK' 00192 00193 def recv_int(self): 00194 ''' This command should not be used on its own: it is called by the execute commands 00195 below in a thread safe manner. 00196 ''' 00197 value = self.recv() 00198 return int(value) 00199 00200 def recv_array(self): 00201 ''' This command should not be used on its own: it is called by the execute commands 00202 below in a thread safe manner. 00203 ''' 00204 try: 00205 values = self.recv().split() 00206 return map(int, values) 00207 except: 00208 return None 00209 00210 def execute(self, cmd): 00211 ''' Thread safe execution of "cmd" on the SerializerTM returning a single value. 00212 ''' 00213 with self.messageLock: 00214 try: 00215 self.port.flushInput() 00216 except: 00217 pass 00218 try: 00219 self.port.write(cmd + '\r') 00220 value = self.recv() 00221 while value == '' or value == 'NACK' or value == None: 00222 self.port.flushInput() 00223 self.port.flushOutput() 00224 self.port.write(cmd + '\r') 00225 value = self.recv() 00226 except: 00227 value = None 00228 return value 00229 00230 def execute_array(self, cmd): 00231 ''' Thread safe execution of "cmd" on the SerializerTM returning an array. 00232 ''' 00233 with self.messageLock: 00234 try: 00235 self.port.flushInput() 00236 except: 00237 pass 00238 try: 00239 self.port.write(cmd + '\r') 00240 values = self.recv_array() 00241 while values == '' or values == ['NACK'] or values == [] or values == None: 00242 time.sleep(0.05) 00243 self.port.flushInput() 00244 self.port.write(cmd + '\r') 00245 values = self.recv_array() 00246 except: 00247 raise SerialException 00248 try: 00249 return map(int, values) 00250 except: 00251 return [] 00252 00253 def execute_ack(self, cmd): 00254 ''' Thread safe execution of "cmd" on the SerializerTM returning True if response is ACK. 00255 ''' 00256 with self.messageLock: 00257 try: 00258 self.port.flushInput() 00259 except: 00260 pass 00261 try: 00262 self.port.write(cmd + '\r') 00263 ack = self.recv() 00264 while ack == '' or ack == 'NACK' or ack == None: 00265 self.port.flushInput() 00266 self.port.write(cmd + '\r') 00267 ack = self.recv() 00268 except: 00269 print "execute_ack exception when executing", cmd 00270 print sys.exc_info() 00271 return 0 00272 return ack == 'ACK' 00273 00274 def execute_int(self, cmd): 00275 ''' Thread safe execution of "cmd" on the SerializerTM returning an int. 00276 ''' 00277 with self.messageLock: 00278 try: 00279 self.port.flushInput() 00280 except: 00281 pass 00282 try: 00283 self.port.write(cmd + '\r') 00284 value = self.recv() 00285 while value == '' or value == 'NACK' or value == None: 00286 self.port.flushInput() 00287 self.port.write(cmd + '\r') 00288 value = self.recv() 00289 except: 00290 print "execute_int exception when executing", cmd 00291 print sys.exc_info() 00292 return None 00293 try: 00294 return int(value) 00295 except: 00296 return None 00297 00298 def update_digital_cache(self, id, value): 00299 with self.messageLock: 00300 if value != "NACK": 00301 self.digital_sensor_cache[id] = value 00302 00303 def update_analog_cache(self, id, value): 00304 with self.messageLock: 00305 if value != "NACK": 00306 self.analog_sensor_cache[id] = value 00307 00308 def get_analog_cache(self, ids): 00309 with self.messageLock: 00310 values = list() 00311 for id in ids: 00312 values.append(self.analog_sensor_cache[id]) 00313 return values 00314 00315 def fw(self): 00316 ''' The fw command returns the current firmware version. 00317 ''' 00318 return self.execute('fw') 00319 00320 def reset(self): 00321 ''' The reset command resets the SerializerTM board and reboots it. You 00322 will see the SerializerTM welcome screen appear after a short delay. 00323 Once the welcome string appears, the SerializerTM is ready to accept 00324 commands. 00325 ''' 00326 return self.execute('reset') 00327 00328 def blink_led(self, id, rate): 00329 ''' Usage 1: blink_led(id, rate) 00330 Usage 2: blink_led([id1, id2], [rate1, rate2]) 00331 The blink_led command can blink one of the two onboard green LEDs 00332 simultaneously, or individually. Each complex parameter is comprised 00333 of an <ledId:blinkRate> pair. The ledId specifies which of the two 00334 green LEDs to blink, and blinkRate specifies the delay between blinks. 00335 The minimum blink rate is 1, and the largest is 127. A value of 0 turns 00336 the led off. 00337 ''' 00338 if type(id) == int: id = [id] 00339 if type(rate) == int: rate = [rate] 00340 return self.execute_ack('blink %s' %' '.join(map(lambda x: '%d:%d' %x, zip(id,rate)))) 00341 00342 def get_compass(self, i2c_addr=None): 00343 ''' Usage 1: heading = get_compass() 00344 Usage 2: heading = get_compass(i2c_addr) 00345 The get_compass command queries a Devantech CMPS03 Electronic 00346 compass module attached to the Serializers I2C port. 00347 The current heading is returned in Binary Radians, or BRADS.To 00348 convert BRADS to DEGREES, multiply BRADS by 360/255 (~1.41). 00349 The default I2C address is 0xC0, however another I2C address can be 00350 supplied as an optional parameter. 00351 ''' 00352 return 360. / 255. * self.execute_int('cmps03 %X' %i2c_addr if i2c_addr else 'cmps03' ) 00353 00354 def get_encoder(self): 00355 ''' The get_encoder command returns the encoder type for the SerializerTM, 00356 single (0) or quadrature (1). 00357 ''' 00358 return self.execute_int('cfg enc'); 00359 00360 def set_encoder(self, encoder_type): 00361 ''' The set_encoder command configures the internal encoder type to be either 00362 single (0) or quadrature (1) type. This information is saved in the 00363 EEPROM, so that the configuration will be retained after a reboot. If 00364 you are using a quadrature encoder (dual channels), and the Serializer 00365 is configured for single encoder operation, then the second quadrature 00366 channel will be ignored. Thus make sure the correct encoder type is 00367 configured according to your setup. The cfg enc command without a 00368 parameter returns the value currently stored in EEPROM. 00369 ''' 00370 return self.execute_ack('cfg enc %d' %encoder_type); 00371 00372 def get_baud(self): 00373 ''' Get the current baud rate on the serial port. 00374 ''' 00375 return self.execute_int('cfg baud'); 00376 00377 def set_baud(self, baudrate): 00378 ''' The set_baud command configures the serial baud rate on the 00379 SerializerTM. Values can be 0=2400, 1=4800, 2=9600, 3=19200, 00380 4=57600, or 5=115200. You can also type in the actual baud rate 00381 string as well (e.g. 19200). The default baud rate used to 00382 communicate with the Serializer is 19200. The cfg baud command 00383 without a parameter returns the value currently stored in EEPROM. 00384 ''' 00385 return self.execute_ack('cfg baud %d' %baudrate); 00386 00387 def get_units(self): 00388 ''' The get_units returns the current units used for sensor 00389 readings. Values are 0 for metric mode, 1 for English mode, and 2 for 00390 raw mode. In raw mode, srf04, srf05, pping, and maxez1 return 00391 reading in units of 0.4us. srf08 and srf10 return readings of 1us.. 00392 ''' 00393 return self.execute_int('cfg units') 00394 00395 def set_units(self, units): 00396 ''' The set_units command sets the internal units used for sensor 00397 readings. Values are 0 for metric mode, 1 for English mode, and 2 for 00398 raw mode. In raw mode, srf04, srf05, pping, and maxez1 return 00399 reading in units of 0.4us. srf08 and srf10 return readings of 1us. 00400 The cfg units command without a parameter returns the value 00401 ''' 00402 self.units = units 00403 return self.execute_ack('cfg units %d' %units); 00404 00405 def get_encoder_count(self, id): 00406 ''' Usage 1: get_encoder_count(id) 00407 Usage 2: get_encoder_count([id1, id2]) 00408 The get_encoder_count command returns the values of the encoder 00409 count (channel B) for the specified encoder Id(s). NOTE: The encoder 00410 counts for channel A are used for internal VPID and DPID algorithms. 00411 ''' 00412 if type(id) == int: id=[id] 00413 values = self.execute_array('getenc %s' %' '.join(map(str, id))) 00414 00415 if len(values) != len(id): 00416 print "Encoder count did not match ID count for ids", id 00417 raise SerialException 00418 else: 00419 if self.motors_reversed: 00420 for i in range(len(id)): 00421 values[i] = -1 * values[i] 00422 return values 00423 00424 def clear_encoder(self, id): 00425 ''' Usage 1: clear_encoder(id) 00426 Usage 2: clear_encoder([id1, id2]) 00427 The clear_encoder command clears the values of the encoder 00428 count (channel B) for the specified encoder Id. 00429 ''' 00430 if type(id) == int: id=[id] 00431 return self.execute_ack('clrenc %s' %' '.join(map(str, id))) 00432 00433 def get_io(self, id): 00434 ''' Usage 1: get_io(id) 00435 Usage 2: get_io([id1, id2, id3, ... , idN]) 00436 The get_io command changes the pin, pinId (range 0-12), to an input 00437 (if it was an output), and gets the value of the specified General 00438 Purpose I/O lines on the SerializerTM. The valid range of I/O pin Ids is 00439 0 thru 12. More than one pid can be specified by enter a list as argument. 00440 ''' 00441 if type(id) == int: id=[id] 00442 values = self.execute_array('getio %s' %' '.join(map(str, id))) 00443 n = len(id) 00444 for i in range(n): 00445 self.update_digital_cache(id[i], values[i]) 00446 if n == 1: 00447 return values[0] 00448 else: 00449 return values 00450 00451 def set_io(self, id, val): 00452 ''' Usage 1: set_io(id, val) 00453 Usage 2: set_io([id1, id2, ... , idN], [val1, val2, ..., valN) 00454 The set_io command sets the specified General Purpose I/O line pinId 00455 (range 0-12) on the SerializerTM to the specified value. Each complex 00456 parameter is a <pinId:value> pair, where the valid range of pinId is 0 00457 thru 12, and value can be 0 or 1 which corresponds to 0v or +5V 00458 respectively. Also I/O lines 4,5,6,7, 8 and 9 cannot be used if you 00459 have servos connected to them. Pin 10, 11, and 12 correspond to the 00460 internal h-bridge enable, SCL, and SDA respectively. 00461 ''' 00462 if type(id) == int: id = [id] 00463 if type(val) == int: val = [val] 00464 return self.execute_ack('setio %s' %' '.join(map(lambda x: '%d:%d' %x, zip(id, val)))) 00465 00466 def get_maxez1(self, triggerPin, outputPin): 00467 ''' The maxez1 command queries a Maxbotix MaxSonar-EZ1 sonar 00468 sensor connected to the General Purpose I/O lines, triggerPin, and 00469 outputPin, for a distance, and returns it in Centimeters. NOTE: MAKE 00470 SURE there's nothing directly in front of the MaxSonar-EZ1 upon 00471 power up, otherwise it wont range correctly for object less than 6 00472 inches away! The sensor reading defaults to use English units 00473 (inches). The sensor distance resolution is integer based. Also, the 00474 maxsonar trigger pin is RX, and the echo pin is PW. 00475 ''' 00476 return self.execute_int('maxez1 %d %d' %(triggerPin, outputPin)) 00477 00478 def stop(self): 00479 ''' Stop both motors. 00480 ''' 00481 return self.execute_ack('stop') 00482 00483 def get_vpid(self): 00484 ''' Get the PIDL parameter values. 00485 ''' 00486 pidl = self.execute('vpid') 00487 return map(lambda x: int(x.split(':')[1]), pidl.split()) 00488 00489 def set_vpid(self, prop, integ, deriv, loop): 00490 ''' The set_vpid command sets the PIDL (Proportional, Integral, 00491 Derivative, and Loop) parameters for the Velocity PID control on the 00492 SerializerTM. The PIDL parameters are parsed, and saved (in 00493 eeprom). For more information on PIDL control, see the PIDL 00494 configuration section below. By default the Serializer VPID 00495 parameters are configured to work with our Traxster Robot Kit 00496 ''' 00497 [self.VPID_P, self.VPID_I, self.VPID_D, self.VPID_L] = [prop, integ, deriv, loop] 00498 return self.execute_ack('vpid %d:%d:%d:%d' %(prop, integ, deriv, loop)) 00499 00500 def digo(self, id, dist, vel): 00501 ''' Usage 1: m(id, dist, vel) 00502 Usage 2: digo([id1, id2], [dist1, dist2], [vel1, vel2]) 00503 Simply put, the digo command allows you to command your robot to 00504 travel a specified distance, at a specified speed. This command uses 00505 the internal VPID and DPID algorithms to control velocity and distance. 00506 Therefore, you must have dual motors, and dual wheel encoders 00507 connected to the Serializer motor ports and encoder inputs. 00508 ''' 00509 if type(id) == int: id = [id] 00510 if type(dist) == int: id = [dist] 00511 if type(vel) == int: vel = [vel] 00512 00513 if self.motors_reversed: 00514 for i in range(len(dist)): 00515 dist[i] = -1 * dist[i] 00516 00517 return self.execute('digo %s' %' '.join(map(lambda x: '%d:%d:%d' %x, zip(id, dist, vel)))) 00518 00519 def digo_m_per_s(self, id, dist, vel): 00520 ''' Identical to digo but specifies velocities in meters per second. 00521 ''' 00522 if type(id) == int: id = [id] 00523 if type(dist) == int: id = [dist] 00524 if type(vel) == int: vel = [vel] 00525 00526 spd = list() 00527 for v in vel: 00528 if self.units == 0: 00529 revs_per_second = float(v) / (self.wheel_diameter * math.pi) 00530 elif self.units == 1: 00531 revs_per_second = float(v) / (self.wheel_diameter * math.pi * 2.54 / 100) 00532 ticks_per_loop = revs_per_second * self.encoder_resolution * self.loop_interval * self.gear_reduction 00533 spd.append(int(ticks_per_loop)) 00534 00535 return self.execute('digo %s' %' '.join(map(lambda x: '%d:%d:%d' %x, zip(id, dist, spd)))) 00536 00537 def get_dpid(self): 00538 ''' Get the PIDA parameter values. 00539 ''' 00540 dpid = self.execute('dpid') 00541 return map(lambda x: int(x.split(':')[1]), dpid.split()) 00542 00543 def set_dpid(self, prop, integ, deriv, accel, dead_band): 00544 ''' The set_dpid command gets/sets the PIDA (Proportional, Integral, 00545 Derivative, and Acceleration) parameters for the distance PID control 00546 on the SerializerTM. If the PIDA parameters are absent, the PIDA 00547 values are returned. Otherwise the PIDA parameters are parsed, and 00548 saved (in eeprom). 00549 ''' 00550 [self.DPID_P, self.DPID_I, self.DPID_D, self.DPID_A, self.DPID_B] = [prop, integ, deriv, accel, dead_band] 00551 return self.execute_ack('dpid %d:%d:%d:%d:%d' %(prop, integ, deriv, accel, dead_band)) 00552 00553 def set_rpid(self, r): 00554 ''' The rpid command sets the default PID params known to work with 00555 either the Stinger or Traxster Robotic Kits in the firmware. This makes 00556 it quick and easy to set up the PID params for both robots. 00557 ''' 00558 return self.execute_ack('rpid %c' %r) 00559 00560 def get_pids(self): 00561 ''' Once a digo command is issued, an internal state variable within the 00562 firmware is set to 1, and it stays in that state until the algorithm has 00563 completed. Upon completion, the state is set to 0. The pids 00564 command simply returns the value of the internal variable to 00565 determine if the algorithms is currently busy, or if it has finished, thus 00566 allowing subsequent digo commands to be issued w/o clobbering 00567 previous ones. 00568 ''' 00569 return self.execute_int('pids'); 00570 00571 def pwm(self, id, vel, rate=None): 00572 ''' Usage 1: pwm(id, vel) 00573 Usage 2: pwm(id, vel, rate=r) 00574 Usage 3: pwm([id1, id2], [vel1, vel2]) 00575 Usage 4: pwm([id1, id2], [vel1, vel2], rate=r) 00576 The pwm command sets the Pulse Width Modulation value for 00577 Motor 1 & Motor 2. Each complex parameter is a motor 00578 <motorId:pwm value> pair, where the motor id can be 1 or 2, and the 00579 pwm value can be -100 to 100. Each complex parameter pair is 00580 separated by one or more spaces. 00581 The optional rate parameter allows the 00582 motor(s) speed(s)s to be ramped up or down to the specified speed 00583 from the current motor speed. 00584 ''' 00585 if type(id) == int: id = [id] 00586 if type(vel) == int: vel = [vel] 00587 if rate != None: 00588 cmd = 'pwm r:%d ' %rate + ' '.join(map(lambda x: '%d:%d' %x, zip(id, vel))) 00589 else: 00590 cmd = 'pwm %s' % ' '.join(map(lambda x: '%d:%d' %x, zip(id, vel))) 00591 return self.execute(cmd) 00592 00593 def step(self, dir, speed ,steps): 00594 ''' The step command is used to step a bipolar stepper motor in direction 00595 dir, at the specified speed, for the specified number of steps. 00596 The dir parameter specifies a CW or CCW rotational direction, and its 00597 value can be either 0 (CCW) or 1(CW). Your specific direction is based 00598 on the way that you have your bipolar motor connected to the 00599 Serializer. The speed parameter can be a value from 0 to 100. 00600 The steps parameter specifies the maximum number of steps to take. 00601 A value of 0 means step infinitely. Internally, this number is stored in 00602 an unsigned 32 bit variable, so the user can specify a larger number of 00603 steps. 00604 ''' 00605 return self.execute_ack('step %d %d %d' %(dir, speed, steps)) 00606 00607 def sweep(self, id, speed, steps): 00608 ''' The sweep command is used to sweep a bipolar motor, for step 00609 number of steps, at speed (0-100), thus providing a sweeping motion. 00610 The initial rotational direction of sweep is in the CW direction. 00611 Upon initial receipt of the command, the firmware will sweep the 00612 motor for 1/2 of the number of steps specified, starting in a CW 00613 direction. Once that number of steps has occurred, the sweep 00614 direction will change, and subsequent sweeps will rotate for the full 00615 amount of steps. Thus, the starting point for the motor is in the 00616 middle of each sweep. You may stop the sweep by either issuing a sweep 00617 command w a 0 speed, or simply sending a stop command. 00618 ''' 00619 return self.execute_ack('sweep %d %d %d' %(id, speed, steps)) 00620 00621 def sensor(self, id): 00622 ''' Usage 1: reading = sensor(id) 00623 Usage 2: readings = sensor([id1, id2, ..., idN]) 00624 The sensor command returns the raw A/D (8 bit) reading from the 00625 analog sensor ports 0-5. Multiple values can be read at a time by 00626 specifying multiple pins as a list. Pin 5 is 1/3 of 00627 the voltage of the power supply for the SerializerTM. To calculate the 00628 battery voltage, simply multiply the value returned by Sensor 5 by 00629 15/1024. 00630 ''' 00631 if type(id) == int: id = [id] 00632 values = self.execute_array('sensor %s' %' '.join(map(str, id))) 00633 n = len(values) 00634 if n != len(id): 00635 print "Array size incorrect: returning cached values for sensors", id 00636 values = self.get_analog_cache(id) 00637 if len(values) == 1: 00638 return values[0] 00639 else: 00640 return values 00641 try: 00642 for i in range(n): 00643 if values[i] == None: 00644 values[i] = self.BAD_VALUE 00645 for i in range(n): 00646 self.update_analog_cache(id[i], values[i]) 00647 if n == 1: 00648 return values[0] 00649 else: 00650 return values 00651 except: 00652 print "Exception reading analog sensors: returning cached values for sensors", id 00653 return self.analog_sensor_cache 00654 00655 00656 def get_analog(self, id): 00657 return self.sensor(id) 00658 00659 def get_all_analog(self): 00660 ''' Return the readings from all analog ports. 00661 ''' 00662 return self.sensor(range(self.N_ANALOG_PORTS)) 00663 00664 def servo(self, id, pos): 00665 ''' Usage 1: servo(id, pos) 00666 Usage 2: servo([id1, id2, ... , idN], [pos1, pos2, ..., posN) 00667 The servo command sets a servo connected to General Purpose I/O 00668 port the specified position. The value of the position can range from 00669 -99 to 100, where 0 is the center position. Setting the position to -100 00670 will disable the servo, allowing it to turn freely by hand. 00671 Each parameter is a <servo id:position> pair, where the servo 00672 id can be 1,2,3,4,5, or 6. 00673 ''' 00674 if type(id) == int: id = [id] 00675 if type(pos) == int: pos = [pos] 00676 return self.execute_ack('servo %s' %' '.join(map(lambda x: '%d:%d' %x, zip(id, pos)))) 00677 00678 def sp03(self, msg, i2c_addr=None): 00679 ''' Usage1: sp03(msg) 00680 Usage2: sp03(msg, ic2_addr) 00681 The sp03 command instructs a Devantech SP03 Speech Synthesizer to 00682 speak the appropriate phrase. If a character representing a number in 00683 the range of 0 to 30, then the SP03 will speak previously programmed 00684 canned phrases. If a phrase is sent, then it will speak the phrase. An 00685 optional I2C address can also be specified. Otherwise, the default I2C 00686 address of 0xC4. 00687 ''' 00688 return self.execute_ack('sp03 0x%X %s' %(i2c_addr, msg) if i2c_addr else 'sp03 %s' %msg) 00689 00690 def srf04(self, triggerPin, outputPin): 00691 ''' The srf04 command queries an SRF04 sonar sensor 00692 connected to the General Purpose I/O lines triggerPin and outputPin, 00693 for a distance and returns it in the units configured (default is English 00694 inches). If the Serializer units are configured (using cfg units) for raw mode, 00695 srf04 returns readings in units of 0.4us, and the max distance returned 00696 is 65000 (out of range). When configured for English units, max 00697 distance returned is 100 inches (out of range), and when configured 00698 for Metric units, max distance returned is 255 (out of range). NOTE: 00699 Sonar distance resolution is integer based. 00700 ''' 00701 return self.execute_int('srf04 %d %d' %(triggerPin, outputPin)) 00702 00703 def srf05(self, pinId): 00704 ''' The srf05/Ping command queries an SRF05/Ping sonar sensor 00705 connected to the General Purpose I/O line pinId for a distance, 00706 and returns it in the units configured (default is English - inches). 00707 If the Serializer units are configured (using cfg units) for raw mode, 00708 pping and srf05 return readings in units of 0.4us, and the max 00709 distance returned is 65000 (out of range). When configured for 00710 English units, max distance returned is 100 inches (out of range), and 00711 when configured for Metric units, max distance returned is 255 (out of 00712 range). Sonar distance resolution is integer based. 00713 ''' 00714 return self.execute_int('srf05 %d' %pinId); 00715 00716 def pping(self, pinId): 00717 ''' The srf05/Ping command queries an SRF05/Ping sonar sensor 00718 connected to the General Purpose I/O line pinId for a distance, 00719 and returns it in the units configured (default is English - inches). 00720 If the Serializer units are configured (using cfg units) for raw mode, 00721 pping and srf05 return readings in units of 0.4us, and the max 00722 distance returned is 65000 (out of range). When configured for 00723 English units, max distance returned is 100 inches (out of range), and 00724 when configured for Metric units, max distance returned is 255 (out of 00725 range). Sonar distance resolution is integer based. 00726 ''' 00727 value = self.execute_int('pping %d' %pinId); 00728 self.update_digital_cache(pinId, value) 00729 return value 00730 00731 def srf08(self, i2c_addr=None): 00732 ''' Usage1: srf08() 00733 Usage2: srf08(ic2_addr) 00734 The srf08/srf10 command queries a Devantech SRF08/SRF10 sonar 00735 sensor at address i2c_addr for a distance reading in the units 00736 configured (default is English - inches). The i2cAddr parameter is 00737 optional, and defaults to 0xE0 for both sensors. The i2c address can 00738 be changed for any i2c module using the i2cp command. Sonar 00739 distance resolution is integer based. If the Serializer units are 00740 configured (using cfg units) for raw mode, srf08 and srf10 return 00741 readings in units of 1us. 00742 ''' 00743 return self.execute_int('srf08 0x%X' %i2c_addr if i2c_addr else 'srf08') 00744 00745 def srf10(self, i2caddr=None): 00746 ''' Usage1: srf10() 00747 Usage2: srf10(ic2_addr) 00748 The srf08/srf10 command queries a Devantech SRF08/SRF10 sonar 00749 sensor at address ic2_addr for a distance reading in the units 00750 configured (default is English - inches). The ic2_addr parameter is 00751 optional, and defaults to 0xE0 for both sensors. The i2c address can 00752 be changed for any i2c module using the i2cp command. Sonar 00753 distance resolution is integer based. If the Serializer units are 00754 configured (using cfg units) for raw mode, srf08 and srf10 return 00755 readings in units of 1us. 00756 ''' 00757 return self.execute_int('srf10 0x%X' %i2caddr if i2caddr else 'srf10') 00758 00759 def tpa81(self, i2caddr=None): 00760 ''' Usage1: tpa81() 00761 Usage2: tpa81(ic2_addr) 00762 The tpa81 command queries a Devantech TPA81 thermopile sensor for 00763 temperature values. It returns 8 temperature values. 00764 ''' 00765 return self.execute_array('tpa81 0x%X' %i2caddr if i2caddr else 'tpa81') 00766 00767 def vel(self): 00768 ''' The vel command returns the left and right wheel velocities. The 00769 velocity returned is based on the PIDL parameter configuration. The 00770 units are encoder ticks per PID loop interval. 00771 ''' 00772 return self.execute_array('vel') 00773 00774 def vel_m_per_s(self): 00775 ''' Return the left and right wheel velocities in meters per second. 00776 ''' 00777 [left_ticks_per_loop, right_ticks_per_loop] = self.vel() 00778 left_revs_per_second = float(left_ticks_per_loop) / self.encoder_resolution / self.loop_interval 00779 right_revs_per_second = float(right_ticks_per_loop) / self.encoder_resolution / self.loop_interval 00780 if self.units == 0: 00781 left_m_s = left_revs_per_second * self.wheel_diameter * math.pi 00782 right_m_s = right_revs_per_second * self.wheel_diameter * math.pi 00783 elif self.units == 1: 00784 left_m_s = left_revs_per_second * self.wheel_diameter * 2.54 * math.pi / 100 00785 right_m_s = right_revs_per_second * self.wheel_diameter * 2.54 * math.pi / 100 00786 return list([left_m_s, right_m_s]) 00787 00788 def vel_mph(self): 00789 ''' Return the left and right wheel velocities in miles per hour. 00790 ''' 00791 [left_m_s, right_m_s] = self.vel_m_per_s() 00792 m_s_2_mph = 2.25 00793 return list([left_m_s * m_s_2_mph, right_m_s * m_s_2_mph]) 00794 00795 def vel_fps(self): 00796 ''' Return the left and right wheel velocities in feet per second. 00797 ''' 00798 [left_m_s, right_m_s] = self.vel_m_per_s() 00799 m_s_2_fps = 3.2808 00800 return list([left_m_s * m_s_2_fps, right_m_s * m_s_2_fps]) 00801 00802 def restore(self): 00803 ''' Restores the factory default settings, and resets the board. NOTE: 00804 This will erase any configurations you have saved to EEPROM, 00805 including VPID, DPID, and baud rate settings. 00806 ''' 00807 print self.execute('restore') 00808 00809 def line(self, addr, newaddr=None, seven=False): 00810 ''' Queries a RoboticsConnection Line Following Sensor at address addr. 00811 If the -a option is specified, then the address of the module will be 00812 changed to the new address associated w the -a switch. 00813 If the optional 7 is appended to the end of the line command, e.g. 00814 line7, then two additional values will be returned from those Line 00815 Following Sensors (manufactured after 11/1/07) which have additional 00816 sensor inputs on the sides of the board. This can be used to read 00817 additional Single Line Following sensors, or read any type of on/off 00818 momentary switch, such those used for bumpers. 00819 ''' 00820 cmd = ('line7 %d' if seven else 'line %d') %addr 00821 if newaddr: cmd += ' -a %d' %newaddr 00822 return self.execute_array(cmd) 00823 00824 def i2c(self, op, addr, data=None): 00825 ''' Usage1: i2c(op, addr) 00826 Usage2: i2c(op, addr, data) 00827 The flexible i2c command allows you to execute a generic i2c read, or 00828 write command to the specified device at address addr. Depending on 00829 whether you issue a read or write, additional parameters vary. 00830 ''' 00831 cmd = 'i2c %c 0x%X ' %(op, addr) 00832 if data: 00833 cmd += ''.join(data) 00834 if op == 'w': 00835 return self.execute_ack(cmd) 00836 else: 00837 return self.execute_array(cmd) 00838 00839 def voltage(self, cached=False): 00840 if cached: 00841 try: 00842 value = self.analog_sensor_cache[5] 00843 except: 00844 try: 00845 value = self.sensor(5) 00846 self.update_analog_cache(5, value) 00847 except: 00848 return None 00849 else: 00850 try: 00851 value = self.sensor(5) 00852 self.update_analog_cache(5, value) 00853 except: 00854 return None 00855 00856 return value * 15. / 1024. 00857 00858 def set_wheel_diameter(self, diameter): 00859 self.wheel_diameter = diameter 00860 00861 def get_wheel_diameter(self): 00862 return self.wheel_diameter 00863 00864 def set_wheel_track(self, track): 00865 self.wheel_track = track 00866 00867 def get_wheel_track(self): 00868 return self.wheel_track 00869 00870 def set_gear_reduction(self, ratio): 00871 self.gear_reduction = ratio 00872 00873 def get_gear_reduction(self): 00874 return self.gear_reduction 00875 00876 def set_encoder_resolution(self, ticks): 00877 self.encoder_resolution = ticks 00878 00879 def get_encoder_resolution(self): 00880 return self.encoder_resolution 00881 00882 def get_Ping(self, pin, cached=False): 00883 ''' Get the distance reading from a Ping sonarl sensor on the given GPIO pin. 00884 ''' 00885 if cached: 00886 value = self.digital_sensor_cache[pin] 00887 else: 00888 value = self.pping(pin) 00889 return value 00890 00891 def get_MaxEZ1(self, trigger_pin, output_pin, cached=False): 00892 ''' Get the distance reading from a MaxEZ1 sonarl sensor on the given trigger and output pins. 00893 ''' 00894 if cached: 00895 value = self.digital_sensor_cache[trigger_pin] 00896 else: 00897 value = self.get_maxez1(trigger_pin, output_pin) 00898 return value 00899 00900 def get_GP2D12(self, pin, cached=False): 00901 ''' Get the distance reading from a GP2D12 IR sensor on the given analog pin. 00902 ''' 00903 if cached: 00904 value = self.analog_sensor_cache[pin] 00905 else: 00906 value = self.sensor(pin) 00907 try: 00908 distance = (6787 / (value - 3)) - 4 00909 except: 00910 distance = 80 00911 if distance > 80: distance = 80 00912 if distance < 10: distance = 10 00913 if self.units == 0: 00914 return distance 00915 elif self.units == 1: 00916 return distance / 2.54 00917 else: 00918 return value 00919 00920 def get_PhidgetsTemperature(self, pin, cached=False, units="F"): 00921 ''' Get the temperature from a Phidgets Temperature sensor on an analog sensor port and return 00922 the reading in either Farhenheit or Celcius depending on the units argument. 00923 ''' 00924 self.temp_units = units 00925 if cached: 00926 value = self.analog_sensor_cache[pin] 00927 else: 00928 value = self.sensor(pin) 00929 try: 00930 tempC = (value - 200.) / 4. 00931 if self.temp_units == "C": 00932 return tempC 00933 else: 00934 return 9. * tempC / 5. + 32. 00935 except: 00936 return self.BAD_VALUE 00937 00938 def get_PhidgetsVoltage(self, pin, cached=False): 00939 ''' Get the voltage from a Phidgets Voltage sensor on an analog sensor port. 00940 ''' 00941 if cached: 00942 value = self.analog_sensor_cache[pin] 00943 else: 00944 value = self.sensor(pin) 00945 try: 00946 return 0.06 * (value - 500.) 00947 except: 00948 return self.BAD_VALUE 00949 00950 def get_PhidgetsCurrent(self, pin, cached=False, model=20, ac_dc="dc"): 00951 if cached: 00952 value = self.analog_sensor_cache[pin] 00953 else: 00954 value = self.sensor(pin) 00955 try: 00956 if model == 20: 00957 if ac_dc == "dc": 00958 return 0.05 * (value - 500.) 00959 else: 00960 return 0.025 * value 00961 else: 00962 if ac_dc == "dc": 00963 return 0.125 * (value - 500.) 00964 else: 00965 return 0.625 * value 00966 except: 00967 return self.BAD_VALUE 00968 00969 def travel_distance(self, dist, vel): 00970 ''' Move forward or backward 'dist' (inches or meters depending on units) at speed 'vel'. Use negative distances 00971 to move backward. 00972 ''' 00973 00974 revs_per_second = float(vel) / (self.wheel_diameter * math.pi) 00975 00976 ticks_per_loop = revs_per_second * self.encoder_resolution * self.loop_interval * self.gear_reduction 00977 vel = int(ticks_per_loop) 00978 00979 revs = dist / (self.wheel_diameter * math.pi) 00980 ticks = revs * self.encoder_resolution * self.gear_reduction 00981 self.digo([1, 2], [ticks, ticks], [vel, vel]) 00982 00983 def mogo(self, id, vel): 00984 ''' Usage 1: mogo(id, vel) 00985 Usage 2: mogo([id1, id2], [vel1, vel2]) 00986 The mogo command sets motor speed using one or more complex 00987 parameters containing a <motorId:spd> value pair. 00988 The motorId can be either 1 or 2, which corresponds to the Motor 00989 Terminal port. 00990 The vel value specifies the motor velocity, and it's range depends on 00991 your VPID settings. See the VPID parameters section below to 00992 determine your MAX velocity. A positive value rotates the motors in 00993 one direction, which a negative value rotates the motors in the 00994 opposite direction. 00995 You will have to determine which direction is positive for your motors, 00996 and connect the motors wires to the terminals on the Serializer board 00997 in the appropriate configuration. 00998 ''' 00999 if type(id) == int: id = [id] 01000 if type(vel) == int: vel = [vel] 01001 01002 if self.motors_reversed: 01003 for i in range(len(vel)): 01004 vel[i] = -1 * vel[i] 01005 01006 return self.execute_ack('mogo %s' %' '.join(map(lambda x: '%d:%d' %x, zip(id, vel)))) 01007 01008 def mogo_m_per_s(self, id, vel): 01009 ''' Set the motor speeds in meters per second. 01010 ''' 01011 if type(id) != list: id = [id] 01012 if type(vel) != list: vel = [vel] 01013 spd = list() 01014 for v in vel: 01015 if self.units == 0: 01016 revs_per_second = float(v) / (self.wheel_diameter * math.pi) 01017 elif self.units == 1: 01018 revs_per_second = float(v) / (self.wheel_diameter * math.pi * 2.54 / 100) 01019 ticks_per_loop = revs_per_second * self.encoder_resolution * self.loop_interval * self.gear_reduction 01020 spd.append(int(ticks_per_loop)) 01021 01022 if self.motors_reversed: 01023 for i in range(len(spd)): 01024 spd[i] = -1 * spd[i] 01025 01026 cmd = 'mogo %s' %' '.join(map(lambda x: '%d:%d' %x, zip(id, spd))) 01027 01028 return self.execute_ack(cmd) 01029 01030 def travel_at_speed(self, id, vel): 01031 ''' Move forward or backward at speed 'vel' in meters per second. Use negative speeds 01032 to move backward. This is just an alias for mogo_m_per_s so see that function for 01033 more details. 01034 ''' 01035 self.mogo_m_per_s(id, vel) 01036 01037 def rotate(self, angle, vel): 01038 ''' Rotate the robot through 'angle' degrees or radians at speed 'vel'. Use the ROS convention for right handed 01039 coordinate systems with the z-axis pointing up so that a positive angle is counterclockwise. 01040 Use negative angles to rotate clockwise. 01041 ''' 01042 if self.units == 0: 01043 revs_per_second = float(vel) / (2.0 * math.pi) 01044 rotation_fraction = angle / (2.0 * math.pi) 01045 full_rotation_dist = self.wheel_track * math.pi 01046 elif self.units == 1: 01047 revs_per_second = float(vel) / 360. 01048 rotation_fraction = angle / 360. 01049 full_rotation_dist = self.wheel_track * 2.54 / 100 * math.pi 01050 01051 vel = revs_per_second * full_rotation_dist # in m/s 01052 01053 rotation_dist = rotation_fraction * full_rotation_dist 01054 revs = rotation_dist / (self.wheel_diameter * math.pi) 01055 01056 ticks = revs * self.encoder_resolution * self.gear_reduction 01057 self.digo_m_per_s([1, 2], [ticks, -ticks], [vel, vel]) 01058 01059 def rotate_at_speed(self, vel): 01060 ''' Rotate the robot continously at speed 'vel' radians or degrees per second. Use the ROS convention for right handed 01061 coordinate systems with the z-axis pointing up so that a positive speed is counterclockwise. 01062 Use negative speeds to rotate clockwise. 01063 ''' 01064 01065 if self.units == 1: 01066 vel = vel / 180. * math.pi 01067 01068 # Check that the user does not mistaken degrees for radians. 01069 if vel > 5.0: 01070 print "That is a rather high rotation rate. Are you sure you specified rotation velocity in the correct units?" 01071 print "Degrees per second for English units and radians per second for metric." 01072 print "Keep in mind that 1 radian per second is about 60 degrees per second." 01073 os._exit(1) 01074 01075 if self.units == 1: 01076 full_rotation_dist = self.wheel_track * 2.54 / 100 * math.pi 01077 revs_per_second = float(vel) / 360. 01078 01079 else: 01080 full_rotation_dist = self.wheel_track * math.pi 01081 revs_per_second = float(vel) / (2.0 * math.pi) 01082 01083 vel = revs_per_second * full_rotation_dist 01084 01085 self.mogo_m_per_s([1, 2], [-vel, vel]) 01086 01087 def twist(self, twist): 01088 angle = math.atan2(twist.linear.y, twist.linear.x) 01089 self.rotate(angle, twist.angular.z) 01090 while self.get_pids(): 01091 time.sleep(0.05) 01092 speed = math.sqrt(twist.linear.x * twist.linear.x + twist.linear.y * twist.linear.y) 01093 self.mogo_m_per_s([1, 2], [speed, speed]) 01094 01095 class Linear: 01096 def __init__(self): 01097 self.x = 0 01098 self.y = 0 01099 self.z = 0 01100 01101 class Angular: 01102 def __init__(self): 01103 self.x = 0 01104 self.y = 0 01105 self.z = 0 01106 01107 class Twist: 01108 def __init__(self): 01109 self.linear = Linear() 01110 self.angular = Angular() 01111 01112 class PhidgetsTemperature(): 01113 def __init__(self, serializer, pin, units="F"): 01114 ''' Usage: myTemp = PhidgetsTemperature(serializer, pin) 01115 reading = myTemp.value() 01116 reading = myTemp.value(cached=True) # gets value from the cache 01117 The Phidgets Temperature Sensor class wraps an analog sensor port and converts the raw 01118 sensor reading to either Farhenheit or Celcius depending on the units argument. 01119 ''' 01120 self.serializer = serializer 01121 self.pin = pin 01122 self.temp_units = units 01123 01124 def value(self, cached=False, units="F"): 01125 return self.serializer.get_PhidgetsTemperature(self.pin, cached, units) 01126 01127 01128 class PhidgetsVoltage(): 01129 def __init__(self, serializer, pin): 01130 ''' Usage: myVolts = PhidgetsVoltage(serializer, pin) 01131 reading = myVolts.value() 01132 reading = myVolts.value(cached=True) # gets value from the cache 01133 The Phidgets Voltage Sensor class wraps an analog sensor port and converts the raw 01134 sensor reading to volts. 01135 ''' 01136 self.serializer = serializer 01137 self.pin = pin 01138 01139 def value(self, cached=False): 01140 return self.serializer.get_PhidgetsVoltage(self.pin, cached) 01141 01142 01143 class PhidgetsCurrent(): 01144 def __init__(self, serializer, pin, model=20, ac_dc="dc"): 01145 ''' Usage: myAmps = PhidgetsCurrent(serializer, pin) 01146 reading = myAmps.value() 01147 reading = myAmps.value(cached=True) # gets value from the cache 01148 The Phidgets Current Sensor class wraps an analog sensor port and converts the raw 01149 sensor reading to amps. Note there are two models of the Phidgets current sensor, 01150 one with a 20 amp max and the other with a 50 amp max. Also, either model can 01151 measure either DC or AC current. 01152 ''' 01153 self.serializer = serializer 01154 self.pin = pin 01155 self.model = model 01156 self.ac_dc = ac_dc 01157 01158 def value(self, cached=False): 01159 return self.serializer.get_PhidgetsCurrent(self.pin, cached, self.model, self.ac_dc) 01160 01161 01162 class Ping(): 01163 def __init__(self, serializer, pin): 01164 ''' Usage: myPing = Ping(serializer, pin) 01165 reading = myPing.value() 01166 reading = myPing.value(cached=True) # gets value from the cache 01167 The Parallax Ping Sonar Sensor class wraps a digital sensor port returns the value 01168 from the pping() command which in turn is in inches or cm depending on the units settings. 01169 ''' 01170 self.serializer = serializer 01171 self.pin = pin 01172 01173 def value(self, cached=False): 01174 return self.serializer.get_Ping(self.pin, cached) 01175 01176 class GP2D12(): 01177 def __init__(self, serializer, pin): 01178 ''' Usage: myIR = GP2D12(serializer, pin) 01179 reading = myIR.value() 01180 reading = myIR.value(cached=True) # gets value from the cache 01181 The Sharp GPD12 IR Sensor class wraps an analog sensor port and converts the raw 01182 sensor reading to either inches or cm depending on the units settings. 01183 ''' 01184 self.serializer = serializer 01185 self.pin = pin 01186 01187 def value(self, cached=False): 01188 return self.serializer.get_GP2D12(self.pin, cached) 01189 01190 01191 """ Basic test for connectivity """ 01192 if __name__ == "__main__": 01193 if os.name == "posix": 01194 portName = "/dev/ttyUSB0" 01195 #portName = "/dev/rfcomm0" # For bluetooth on Linux 01196 # Note: On Linux, after connecting to the Bluetooth adapter, run the command 01197 # sudo rfcomm bind /dev/rfcomm0 01198 else: 01199 portName = "COM43" # Windows style COM port. 01200 01201 baudRate = 19200 01202 01203 mySerializer = Serializer(port=portName, baudrate=baudRate, timeout=5) 01204 mySerializer.connect() 01205 01206 time.sleep(2) 01207 01208 print "Firmware Version", mySerializer.fw() 01209 print "Units", mySerializer.get_units() 01210 print "Baudrate", mySerializer.get_baud() 01211 print "VPID", mySerializer.get_vpid() 01212 print "DPID", mySerializer.get_dpid() 01213 print "Encoder ticks per meter", mySerializer.ticks_per_meter 01214 print "Voltage", mySerializer.voltage() 01215 01216 print "Connection test successful, now shutting down...", 01217 01218 mySerializer.stop() 01219 mySerializer.close() 01220 01221 print "Shutting down Serializer." 01222