sphero_driver.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 #***********************************************************
00003 #* Software License Agreement (BSD License)
00004 #*
00005 #*  Copyright (c) 2012, Melonee Wise
00006 #*  All rights reserved.
00007 #*
00008 #*  Redistribution and use in source and binary forms, with or without
00009 #*  modification, are permitted provided that the following conditions
00010 #*  are met:
00011 #*
00012 #*   * Redistributions of source code must retain the above copyright
00013 #*     notice, this list of conditions and the following disclaimer.
00014 #*   * Redistributions in binary form must reproduce the above
00015 #*     copyright notice, this list of conditions and the following
00016 #*     disclaimer in the documentation and/or other materials provided
00017 #*     with the distribution.
00018 #*
00019 #*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00020 #*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00021 #*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00022 #*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00023 #*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00024 #*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00025 #*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00026 #*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00027 #*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00028 #*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00029 #*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00030 #*  POSSIBILITY OF SUCH DAMAGE.
00031 #***********************************************************
00032 #author: Melonee Wise
00033 
00034 import bluetooth
00035 import sys
00036 import struct
00037 import time
00038 import operator
00039 import threading
00040 
00041 #These are the message response code that can be return by Sphero.
00042 MRSP = dict(
00043   ORBOTIX_RSP_CODE_OK = 0x00,           #Command succeeded
00044   ORBOTIX_RSP_CODE_EGEN = 0x01,         #General, non-specific error
00045   ORBOTIX_RSP_CODE_ECHKSUM = 0x02,      #Received checksum failure
00046   ORBOTIX_RSP_CODE_EFRAG = 0x03,        #Received command fragment
00047   ORBOTIX_RSP_CODE_EBAD_CMD = 0x04,     #Unknown command ID
00048   ORBOTIX_RSP_CODE_EUNSUPP = 0x05,      #Command currently unsupported
00049   ORBOTIX_RSP_CODE_EBAD_MSG = 0x06,     #Bad message format
00050   ORBOTIX_RSP_CODE_EPARAM = 0x07,       #Parameter value(s) invalid
00051   ORBOTIX_RSP_CODE_EEXEC = 0x08,        #Failed to execute command
00052   ORBOTIX_RSP_CODE_EBAD_DID = 0x09,     #Unknown device ID
00053   ORBOTIX_RSP_CODE_POWER_NOGOOD = 0x31, #Voltage too low for refash operation
00054   ORBOTIX_RSP_CODE_PAGE_ILLEGAL = 0x32, #Illegal page number provided
00055   ORBOTIX_RSP_CODE_FLASH_FAIL = 0x33,   #Page did not reprogram correctly
00056   ORBOTIX_RSP_CODE_MA_CORRUPT = 0x34,   #Main application corrupt
00057   ORBOTIX_RSP_CODE_MSG_TIMEOUT = 0x35)  #Msg state machine timed out
00058 
00059 
00060 #ID codes for asynchronous packets
00061 IDCODE = dict(
00062   PWR_NOTIFY = chr(0x01),               #Power notifications
00063   LEVEL1_DIAG = chr(0x02),              #Level 1 Diagnostic response
00064   DATA_STRM = chr(0x03),                #Sensor data streaming
00065   CONFIG_BLOCK = chr(0x04),             #Config block contents
00066   SLEEP = chr(0x05),                    #Pre-sleep warning (10 sec)
00067   MACRO_MARKERS =chr(0x06),             #Macro markers
00068   COLLISION = chr(0x07))                #Collision detected
00069 
00070 RECV = dict(
00071   ASYNC = [chr(0xff), chr(0xfe)],
00072   SYNC = [chr(0xff), chr(0xff)])
00073 
00074 
00075 REQ = dict(
00076   WITH_RESPONSE =[0xff, 0xff],
00077   WITHOUT_RESPONSE =[0xff, 0xfe],
00078   CMD_PING = [0x00, 0x01],
00079   CMD_VERSION = [0x00, 0x02],
00080   CMD_SET_BT_NAME = [0x00, 0x10],
00081   CMD_GET_BT_NAME = [0x00, 0x11],
00082   CMD_SET_AUTO_RECONNECT = [0x00, 0x12],
00083   CMD_GET_AUTO_RECONNECT = [0x00, 0x13],
00084   CMD_GET_PWR_STATE = [0x00, 0x20],
00085   CMD_SET_PWR_NOTIFY = [0x00, 0x21],
00086   CMD_SLEEP = [0x00, 0x22],
00087   CMD_GOTO_BL = [0x00, 0x30],
00088   CMD_RUN_L1_DIAGS = [0x00, 0x40],
00089   CMD_RUN_L2_DIAGS = [0x00, 0x41],
00090   CMD_CLEAR_COUNTERS = [0x00, 0x42],
00091   CMD_ASSIGN_COUNTER = [0x00, 0x50],
00092   CMD_POLL_TIMES = [0x00, 0x51],
00093   CMD_SET_HEADING = [0x02, 0x01],
00094   CMD_SET_STABILIZ = [0x02, 0x02],
00095   CMD_SET_ROTATION_RATE = [0x02, 0x03],
00096   CMD_SET_APP_CONFIG_BLK = [0x02, 0x04],
00097   CMD_GET_APP_CONFIG_BLK = [0x02, 0x05],
00098   CMD_SET_DATA_STRM = [0x02, 0x11],
00099   CMD_CFG_COL_DET = [0x02, 0x12],
00100   CMD_SET_RGB_LED = [0x02, 0x20],
00101   CMD_SET_BACK_LED = [0x02, 0x21],
00102   CMD_GET_RGB_LED = [0x02, 0x22],
00103   CMD_ROLL = [0x02, 0x30],
00104   CMD_BOOST = [0x02, 0x31],
00105   CMD_SET_RAW_MOTORS = [0x02, 0x33],
00106   CMD_SET_MOTION_TO = [0x02, 0x34],
00107   CMD_GET_CONFIG_BLK = [0x02, 0x40],
00108   CMD_SET_DEVICE_MODE = [0x02, 0x42],
00109   CMD_SET_CFG_BLOCK = [0x02, 0x43],
00110   CMD_GET_DEVICE_MODE = [0x02, 0x44],
00111   CMD_RUN_MACRO = [0x02, 0x50],
00112   CMD_SAVE_TEMP_MACRO = [0x02, 0x51],
00113   CMD_SAVE_MACRO = [0x02, 0x52],
00114   CMD_DEL_MACRO = [0x02, 0x53],
00115   CMD_INIT_MACRO_EXECUTIVE = [0x02, 0x54],
00116   CMD_ABORT_MACRO = [0x02, 0x55],
00117   CMD_GET_MACRO_STATUS = [0x02, 0x56],
00118   CMD_SET_MACRO_STATUS = [0x02, 0x57])
00119 
00120 STRM_MASK1 = dict(
00121   GYRO_H_FILTERED    = 0x00000001,
00122   GYRO_M_FILTERED    = 0x00000002,
00123   GYRO_L_FILTERED    = 0x00000004,
00124   LEFT_EMF_FILTERED  = 0x00000020,
00125   RIGHT_EMF_FILTERED = 0x00000040,
00126   MAG_Z_FILTERED     = 0x00000080,
00127   MAG_Y_FILTERED     = 0x00000100,
00128   MAG_X_FILTERED     = 0x00000200,
00129   GYRO_Z_FILTERED    = 0x00000400,
00130   GYRO_Y_FILTERED    = 0x00000800,
00131   GYRO_X_FILTERED    = 0x00001000,
00132   ACCEL_Z_FILTERED   = 0x00002000,
00133   ACCEL_Y_FILTERED   = 0x00004000,
00134   ACCEL_X_FILTERED   = 0x00008000,
00135   IMU_YAW_FILTERED   = 0x00010000,
00136   IMU_ROLL_FILTERED  = 0x00020000,
00137   IMU_PITCH_FILTERED = 0x00040000,
00138   LEFT_EMF_RAW       = 0x00200000,
00139   RIGHT_EMF_RAW      = 0x00400000,
00140   MAG_Z_RAW          = 0x00800000,
00141   MAG_Y_RAW          = 0x01000000,
00142   MAG_X_RAW          = 0x02000000,
00143   GYRO_Z_RAW         = 0x04000000,
00144   GYRO_Y_RAW         = 0x08000000,
00145   GYRO_X_RAW         = 0x10000000,
00146   ACCEL_Z_RAW        = 0x20000000,
00147   ACCEL_Y_RAW        = 0x40000000,
00148   ACCEL_X_RAW        = 0x80000000)
00149 
00150 STRM_MASK2 = dict(
00151   QUATERNION_Q0      = 0x80000000,
00152   QUATERNION_Q1      = 0x40000000,
00153   QUATERNION_Q2      = 0x20000000,
00154   QUATERNION_Q3      = 0x10000000,
00155   ODOM_X             = 0x08000000,
00156   ODOM_Y             = 0x04000000,
00157   ACCELONE           = 0x02000000,
00158   VELOCITY_X         = 0x01000000,
00159   VELOCITY_Y         = 0x00800000)
00160 
00161 
00162 class BTInterface(object):
00163 
00164   def __init__(self, target_name = 'Sphero', port = 1):
00165       self.target_name = target_name
00166       self.port = port
00167       self.found_device = False
00168       self.tries = 0
00169       self.target_address = None
00170       self.sock = None
00171 
00172   def connect(self):
00173     sys.stdout.write("Searching for devices....")
00174     sys.stdout.flush()
00175 
00176     for i in range(10):
00177       sys.stdout.write("....")
00178       sys.stdout.flush()
00179       nearby_devices = bluetooth.discover_devices(lookup_names = True)
00180 
00181       if len(nearby_devices)>0:
00182         for bdaddr, name in nearby_devices:
00183           #look for a device name that starts with Sphero
00184           if name.startswith(self.target_name):
00185             self.found_device = True
00186             self.target_address = bdaddr
00187             break
00188       if self.found_device:
00189         break
00190 
00191 
00192     if self.target_address is not None:
00193       sys.stdout.write("\nFound Sphero device with address: %s\n" %  (self.target_address))
00194       sys.stdout.flush()
00195     else:
00196       sys.stdout.write("\nNo Sphero devices found.\n" )
00197       sys.stdout.flush()
00198       sys.exit(1)
00199 
00200     try:
00201       self.sock=bluetooth.BluetoothSocket(bluetooth.RFCOMM)
00202       self.sock.connect((bdaddr,self.port))
00203     except bluetooth.btcommon.BluetoothError as error:
00204       sys.stdout.write(error)
00205       sys.stdout.flush()
00206       time.sleep(5.0)
00207       sys.exit(1)
00208     sys.stdout.write("Paired with Sphero.\n")
00209     sys.stdout.flush()
00210     return True
00211 
00212   def send(self, data):
00213     self.sock.send(data)
00214 
00215   def recv(self, num_bytes):
00216     return self.sock.recv(num_bytes)
00217 
00218   def close(self):
00219     self.sock.close()
00220 
00221 class Sphero(threading.Thread):
00222 
00223   def __init__(self, target_name = 'Sphero'):
00224     threading.Thread.__init__(self)
00225     self.target_name = target_name
00226     self.bt = None
00227     self.shutdown = False
00228     self.is_connected = False
00229     self.mask_list = None
00230     self.stream_mask1 = None
00231     self.stream_mask2 = None
00232     self.seq = 0
00233     self.raw_data_buf = []
00234     self._communication_lock = threading.Lock()
00235     self._async_callback_dict = dict()
00236     self._sync_callback_dict = dict()
00237     self._sync_callback_queue = []
00238 
00239   def connect(self):
00240     self.bt = BTInterface(self.target_name)
00241     self.is_connected = self.bt.connect()
00242     return True
00243 
00244   def inc_seq(self):
00245     self.seq = self.seq + 1
00246     if self.seq > 0xff:
00247       self.seq = 0
00248 
00249   def pack_cmd(self, req ,cmd):
00250     self.inc_seq()
00251  #   print req + [self.seq] + [len(cmd)+1] + cmd
00252     return req + [self.seq] + [len(cmd)+1] + cmd
00253 
00254   def data2hexstr(self, data):
00255     return ' '.join([ ("%02x"%ord(d)) for d in data])
00256 
00257   def create_mask_list(self, mask1, mask2):
00258     #save the mask
00259     sorted_STRM1 = sorted(STRM_MASK1.iteritems(), key=operator.itemgetter(1), reverse=True)
00260     #create a list containing the keys that are part of the mask
00261     self.mask_list1 = [key  for key, value in sorted_STRM1 if value & mask1]
00262 
00263     sorted_STRM2 = sorted(STRM_MASK2.iteritems(), key=operator.itemgetter(1), reverse=True)
00264     #create a list containing the keys that are part of the mask
00265     self.mask_list2 = [key  for key, value in sorted_STRM2 if value & mask2]
00266     self.mask_list = self.mask_list1 + self.mask_list2
00267 
00268 
00269   def add_async_callback(self, callback_type, callback):
00270     self._async_callback_dict[callback_type] = callback
00271 
00272   def remove_async_callback(self, callback_type):
00273     del self._async_callback_dict[callback_type]
00274 
00275   def add_sync_callback(self, callback_type, callback):
00276     self._sync_callback_dict[callback_type] = callback
00277 
00278   def remove_sync_callback(self, callback_type):
00279     del self._sync_callback_dict[callback_type]
00280 
00281   def clamp(self, n, minn, maxn):
00282     return max(min(maxn, n), minn)
00283     
00284   def ping(self, response):
00285     """
00286     The Ping command is used to verify both a solid data link with the
00287     Client and that Sphero is awake and dispatching commands.
00288 
00289     :param response: request response back from Sphero.
00290     """
00291     self.send(self.pack_cmd(REQ['CMD_PING'],[]), response)
00292 
00293   def get_version(self, response):
00294     """
00295     The Get Versioning command returns a whole slew of software and
00296     hardware information.
00297 
00298     :param response: request response back from Sphero.
00299     """
00300     self.send(self.pack_cmd(REQ['CMD_VERSION'],[]), response)
00301 
00302   def set_device_name(self, name, response):
00303     """
00304     This assigned name is held internally and produced as part of the
00305     Get Bluetooth Info service below. Names are clipped at 48
00306     characters in length to support UTF-8 sequences; you can send
00307     something longer but the extra will be discarded. This field
00308     defaults to the Bluetooth advertising name.
00309 
00310     :param name: 48 character name.
00311     :param response: request response back from Sphero.
00312     """
00313     self.send(self.pack_cmd(REQ['CMD_SET_BT_NAME'],[name]), response)
00314 
00315   def get_bt_name(self, response):
00316     """
00317     This returns the textual name (in ASCII) that the Bluetooth module
00318     advertises. It also returns the BTA Bluetooth Address or MAC ID
00319     for this device. Both values are returned in ASCII and have field
00320     widths of 16 characters, with unused trailing characters set to
00321     00h.
00322 
00323     :param response: request response back from Sphero.
00324     """
00325     self.send(self.pack_cmd(REQ['CMD_GET_BT_NAME'],[]), response)
00326 
00327   def set_auto_reconnect(self, enable, time, response):
00328     """
00329     This configures the control of the Bluetooth module in its attempt
00330     to automatically reconnect with the last iPhone device. This is a
00331     courtesy behavior since the iPhone Bluetooth stack doesn't initiate
00332     automatic reconnection on its own.  The two parameters are simple:
00333     flag = 00h to disable or 01h to enable, and time = the number of
00334     seconds after power-up in which to enable auto reconnect mode. For
00335     example, if time = 30 then the module will be attempt reconnecting 30
00336     seconds after waking up.
00337 
00338     :param enable: 00h to disable or 01h to enable auto reconnecting.
00339     :param time: the number of seconds after power-up in which to\
00340     enable auto reconnect mode
00341     :param response: request response back from Sphero.
00342     """
00343     self.send(self.pack_cmd(REQ['CMD_SET_AUTO_RECONNECT'],[enable,time]), response)
00344 
00345   def get_auto_reconnect(self, response):
00346     """
00347     This returns the Bluetooth auto reconnect values as defined in the
00348     Set Auto Reconnect command.
00349 
00350     :param response: request response back from Sphero.
00351     """
00352     self.send(self.pack_cmd(REQ['CMD_GET_AUTO_RECONNECT'],[]), reponse)
00353 
00354   def get_power_state(self, response):
00355     """
00356     This returns the current power state and some additional
00357     parameters to the Client.
00358 
00359     :param response: request response back from Sphero.
00360     """
00361     self.send(self.pack_cmd(REQ['CMD_GET_PWR_STATE'],[]), response)
00362 
00363   def set_power_notify(self, enable, response):
00364     """
00365     This enables Sphero to asynchronously notify the Client
00366     periodically with the power state or immediately when the power
00367     manager detects a state change. Timed notifications arrive every 10
00368     seconds until they're explicitly disabled or Sphero is unpaired. The
00369     flag is as you would expect, 00h to disable and 01h to enable.
00370 
00371     :param enable: 00h to disable and 01h to enable power notifications.
00372     :param response: request response back from Sphero.
00373     """
00374     self.send(self.pack_cmd(REQ['CMD_SET_PWR_NOTIFY'],[enable]), response)
00375 
00376   def go_to_sleep(self, time, macro, response):
00377     """
00378     This puts Sphero to sleep immediately with two parameters: the
00379     first is the number of seconds after which it will automatically
00380     re-awaken. If set to zero, this feature is disabled. If non-zero then
00381     the MACRO parameter allows an optional system macro to be run upon
00382     wakeup. If this is set to zero, no macro is executed.
00383 
00384     :param time: number of seconds wait before auto re-awake.
00385     :param macro: macro number to run when re-awakened.
00386     :param response: request response back from Sphero.
00387     """
00388     self.send(self.pack_cmd(REQ['CMD_SLEEP'],[(time>>8), (time & 0xff), macro]), response)
00389 
00390   def run_l1_diags(self, response):
00391     """
00392     This is a developer-level command to help diagnose aberrant
00393     behavior. Most system counters, process flags, and system states
00394     are decoded into human readable ASCII. There are two responses to
00395     this command: a Simple Response followed by a large async message
00396     containing the results of the diagnostic tests.
00397 
00398     :param response: request response back from Sphero.
00399     """
00400     self.send(self.pack_cmd(REQ['CMD_RUN_L1_DIAGS'],[]), response)
00401 
00402   def run_l2_diags(self, response):
00403     """
00404     This is a developers-only command to help diagnose aberrant
00405     behavior. It is much less impactful than the Level 1 command as it
00406     doesn't interfere with the current operation it simply returns a
00407     current set of statistics to the client.
00408 
00409     :param response: request response back from Sphero.
00410     """
00411     self.send(self.pack_cmd(REQ['CMD_RUN_L2_DIAGS'],[]), response)
00412 
00413   def clear_counters(self, response):
00414     """
00415     This is a developers-only command to clear the various system
00416     counters described in the level 2 diag.
00417 
00418     :param response: request response back from Sphero.
00419     """
00420     self.send(self.pack_cmd(REQ['CMD_CLEAR_COUNTERS'],[]), response)
00421 
00422   def assign_counter_value(self, counter, response):
00423     """
00424     Sphero contains a 32-bit counter that increments every millisecond
00425     when it's not in the Idle state. It has no absolute meaning and is
00426     reset for various reasons. This command assigns the counter a
00427     specific value for subsequent sampling.
00428 
00429     :param counter: value to set the counter to.
00430     :param response: request response back from Sphero.
00431     """
00432     self.send(self.pack_cmd(REQ['CMD_ASSIGN_COUNTER'],[((counter>>24) & 0xff), ((counter>>16) & 0xff), ((counter>>8) & 0xff) ,(counter & 0xff)]), response)
00433 
00434   def poll_packet_times(self, time, response):
00435     """
00436     This command helps the Client application profile the transmission
00437     and processing latencies in Sphero so that a relative
00438     synchronization of timebases can be performed. It allows the
00439     Client to reconcile time stamped messages from Sphero to its own
00440     time stamped events.
00441 
00442     The scheme is as follows: the Client sends the command with the
00443     Client Tx time (:math:`T_{1}`) filled in. Upon receipt of the packet, the
00444     command processor in Sphero copies that time into the response
00445     packet and places the current value of the millisecond counter
00446     into the Sphero Rx time field (:math:`T_{2}`). Just before the transmit
00447     engine streams it into the Bluetooth module, the Sphero Tx time
00448     value (:math:`T_{3}`)  is filled in. If the Client then records the time at
00449     which the response is received (:math:`T_{4}`) the relevant time segments can
00450     be computed from the four time stamps (:math:`T_{1}, T_{2}, T_{3}, T_{4}`):
00451 
00452     * The value offset represents the maximum-likelihood time offset\
00453       of the Client clock to Sphero's system clock.
00454         * offset :math:`= 1/2*[(T_{2} - T_{1}) + (T_{3}  - T_{4})]`
00455 
00456     * The value delay represents the round-trip delay between the\
00457       Client and Sphero:
00458         * delay :math:`= (T_{4} - T_{1}) - (T_{3} - T_{2})`
00459 
00460     :param time: client Tx time.
00461     :param response: request response back from Sphero.
00462     """
00463     self.send(self.pack_cmd(REQ['CMD_POLL_TIME'],[((time>>24) & 0xff), ((time>>16) & 0xff), ((time>>8) & 0xff), (time & 0xff)]), response)
00464 
00465   def set_heading(self, heading, response):
00466     """
00467     This allows the client to adjust the orientation of Sphero by
00468     commanding a new reference heading in degrees, which ranges from 0
00469     to 359. You will see the ball respond immediately to this command
00470     if stabilization is enabled.
00471 
00472     :param heading: heading in degrees from 0 to 359 (motion will be\
00473     shortest angular distance to heading command)
00474     :param response: request response back from Sphero.
00475     """
00476     self.send(self.pack_cmd(REQ['CMD_SET_HEADING'],[(heading>>8),(heading & 0xff)]), response)
00477 
00478   def set_stablization(self, enable, response):
00479     """
00480     This turns on or off the internal stabilization of Sphero, in
00481     which the IMU is used to match the ball's orientation to its
00482     various set points. The flag value is as you would expect, 00h for
00483     off and 01h for on.
00484 
00485     :param enable: 00h for off and 01h for on (on by default).
00486     :param response: request response back from Sphero.
00487     """
00488     self.send(self.pack_cmd(REQ['CMD_SET_STABILIZ'],[enable]), response)
00489 
00490   def set_rotation_rate(self, rate, response):
00491     """
00492     This allows you to control the rotation rate that Sphero will use
00493     to meet new heading commands. The commanded value is in units of
00494     0.784 degrees/sec. So, setting a value of c8h will set the
00495     rotation rate to 157 degrees/sec. A value of 255 jumps to the
00496     maximum and a value of 1 is the minimum.
00497 
00498     :param rate: rotation rate in units of 0.784degrees/sec (setting\
00499     this value will not cause the device to move only set the rate it\
00500     will move in other funcation calls).
00501     :param response: request response back from Sphero.
00502     """
00503     self.send(self.pack_cmd(REQ['CMD_SET_ROTATION_RATE'],[self.clamp(rate, 0, 255)]), response)
00504 
00505   def set_app_config_blk(self, app_data, response):
00506     """
00507     This allows you to write a 32 byte block of data from the
00508     configuration block that is set aside for exclusive use by
00509     applications.
00510 
00511     :param app_data: block set aside for application.
00512     :param response: request response back from Sphero.
00513     """
00514     self.send(self.pack_cmd(REQ['CMD_SET_APP_CONFIG_BLK'],[((app_data>>24) & 0xff), ((app_data>>16) & 0xff), ((app_data>>8) & 0xff), (app_data & 0xff)]), response)
00515 
00516   def get_app_config_blk(self, response):
00517     """
00518     This allows you to retrieve the application configuration block\
00519     that is set aside for exclusive use by applications.
00520     :param response: request response back from Sphero.
00521     """
00522     self.send(self.pack_cmd(REQ['CMD_GET_APP_CONFIG_BLK'], []), response)
00523 
00524   def set_data_strm(self, sample_div, sample_frames, sample_mask1, pcnt, sample_mask2, response):
00525     """
00526     Currently the control system runs at 400Hz and because it's pretty
00527     unlikely you will want to see data at that rate, N allows you to
00528     divide that down. sample_div = 2 yields data samples at 200Hz,
00529     sample_div = 10, 40Hz, etc. Every data sample consists of a
00530     "frame" made up of the individual sensor values as defined by the
00531     sample_mask. The sample_frames value defines how many frames to
00532     collect in memory before the packet is emitted. In this sense, it
00533     controls the latency of the data you receive. Increasing
00534     sample_div and the number of bits set in sample_mask drive the
00535     required throughput. You should experiment with different values
00536     of sample_div, sample_frames and sample_mask to see what works
00537     best for you.
00538 
00539     :param sample_div: divisor of the maximum sensor sampling rate.
00540     :param sample_frames: number of sample frames emitted per packet.
00541     :param sample_mask1: bitwise selector of data sources to stream.
00542     :param pcnt: packet count (set to 0 for unlimited streaming).
00543     :param response: request response back from Sphero.
00544     """
00545     data = self.pack_cmd(REQ['CMD_SET_DATA_STRM'], \
00546            [(sample_div>>8), (sample_div & 0xff), (sample_frames>>8), (sample_frames & 0xff), ((sample_mask1>>24) & 0xff), \
00547               ((sample_mask1>>16) & 0xff),((sample_mask1>>8) & 0xff), (sample_mask1 & 0xff), pcnt, ((sample_mask2>>24) & 0xff), \
00548               ((sample_mask2>>16) & 0xff),((sample_mask2>>8) & 0xff), (sample_mask2 & 0xff)])
00549     self.create_mask_list(sample_mask1, sample_mask2)
00550     self.stream_mask1 = sample_mask1
00551     self.stream_mask2 = sample_mask2
00552     #print data
00553     self.send(data, response)
00554 
00555   def set_filtered_data_strm(self, sample_div, sample_frames, pcnt, response):
00556     """
00557     Helper function to add all the filtered data to the data strm
00558     mask, so that the user doesn't have to set the data strm manually.
00559     
00560     :param sample_div: divisor of the maximum sensor sampling rate.
00561     :param sample_frames: number of sample frames emitted per packet.
00562     :param pcnt: packet count (set to 0 for unlimited streaming).
00563     :param response: request response back from Sphero.
00564     """
00565     mask1 = 0
00566     mask2 = 0
00567     for key,value in STRM_MASK1.iteritems():
00568       if 'FILTERED' in key:
00569         mask1 = mask1|value
00570     for value in STRM_MASK2.itervalues():
00571         mask2 = mask2|value
00572     self.set_data_strm(sample_div, sample_frames, mask1, pcnt, mask2, response)
00573 
00574   def set_raw_data_strm(self, sample_div, sample_frames, pcnt, response):
00575     """
00576     Helper function to add all the raw data to the data strm mask, so
00577     that the user doesn't have to set the data strm manually.
00578     
00579     :param sample_div: divisor of the maximum sensor sampling rate.
00580     :param sample_frames: number of sample frames emitted per packet.
00581     :param pcnt: packet count (set to 0 for unlimited streaming).
00582     :param response: request response back from Sphero.
00583     """
00584     mask1 = 0
00585     mask2 = 0
00586     for key,value in STRM_MASK1.iteritems():
00587       if 'RAW' in key:
00588         mask1 = mask1|value
00589     for value in STRM_MASK2.itervalues():
00590         mask2 = mask2|value
00591     self.set_data_strm(sample_div, sample_frames, mask1, pcnt, mask2, response)
00592 
00593 
00594   def set_all_data_strm(self, sample_div, sample_frames, pcnt, response):
00595     """
00596     Helper function to add all the data to the data strm mask, so
00597     that the user doesn't have to set the data strm manually.
00598     
00599     :param sample_div: divisor of the maximum sensor sampling rate.
00600     :param sample_frames: number of sample frames emitted per packet.
00601     :param pcnt: packet count (set to 0 for unlimited streaming).
00602     :param response: request response back from Sphero.
00603     """
00604     mask1 = 0
00605     mask2 = 0
00606     for value in STRM_MASK1.itervalues():
00607         mask1 = mask1|value
00608     for value in STRM_MASK2.itervalues():
00609         mask2 = mask2|value
00610     self.set_data_strm(sample_div, sample_frames, mask1, pcnt, mask2, response)
00611 
00612   def config_collision_detect(self, method, Xt, Xspd, Yt, Yspd, ignore_time, response):
00613     """
00614     This command either enables or disables asynchronous message
00615     generation when a collision is detected.The Ignore Time parameter
00616     disables collision detection for a period of time after the async
00617     message is generated, preventing message overload to the
00618     client. The value is in 10 millisecond increments.
00619 
00620     :param method: Detection method type to use. Currently the only\
00621     method supported is 01h. Use 00h to completely disable this\
00622     service.
00623     :param Xt, Yt: An 8-bit settable threshold for the X (left/right)\
00624     and Y (front/back) axes of Sphero. A value of 00h disables the\
00625     contribution of that axis.
00626     :param Xspd,Yspd: An 8-bit settable speed value for the X and Y\
00627     axes. This setting is ranged by the speed, then added to Xt, Yt to\
00628     generate the final threshold value.
00629     :param ignore_time: An 8-bit post-collision dead time to prevent\
00630     retriggering; specified in 10ms increments.
00631     """
00632     self.send(self.pack_cmd(REQ['CMD_CFG_COL_DET'],[method, Xt, Xspd, Yt, Yspd, ignore_time]), response)
00633 
00634   def set_rgb_led(self, red, green, blue, save, response):
00635     """
00636     This allows you to set the RGB LED color. The composite value is
00637     stored as the "application LED color" and immediately driven to
00638     the LED (if not overridden by a macro or orbBasic operation). If
00639     FLAG is true, the value is also saved as the "user LED color"
00640     which persists across power cycles and is rendered in the gap
00641     between an application connecting and sending this command.
00642 
00643     :param red: red color value.
00644     :param green: green color value.
00645     :param blue: blue color value.
00646     :param save: 01h for save (color is saved as "user LED color").
00647     """
00648     self.send(self.pack_cmd(REQ['CMD_SET_RGB_LED'],[self.clamp(red,0,255), self.clamp(green,0,255), self.clamp(blue,0,255), save]), response)
00649 
00650   def set_back_led(self, brightness, response):
00651     """
00652     This allows you to control the brightness of the back LED. The
00653     value does not persist across power cycles.
00654 
00655     :param brightness: 0-255, off-on (the blue LED on hemisphere of the Sphero).
00656     :param response: request response back from Sphero.
00657     """
00658     self.send(self.pack_cmd(REQ['CMD_SET_BACK_LED'],[self.clamp(brightness,0,255)]), response)
00659 
00660   def get_rgb_led(self, response):
00661     """
00662     This retrieves the "user LED color" which is stored in the config
00663     block (which may or may not be actively driven to the RGB LED).
00664 
00665     :param response: request response back from Sphero.
00666     """
00667     self.send(self.pack_cmd(REQ['CMD_GET_RGB_LED'],[]), response)
00668 
00669   def roll(self, speed, heading, state, response):
00670     """
00671     This commands Sphero to roll along the provided vector. Both a
00672     speed and a heading are required; the latter is considered
00673     relative to the last calibrated direction. A state Boolean is also
00674     provided (on or off). The client convention for heading follows the 360
00675     degrees on a circle, relative to the ball: 0 is straight ahead, 90
00676     is to the right, 180 is back and 270 is to the left. The valid
00677     range is 0..359.
00678 
00679     :param speed: 0-255 value representing 0-max speed of the sphero.
00680     :param heading: heading in degrees from 0 to 359.
00681     :param state: 00h for off (braking) and 01h for on (driving).
00682     :param response: request response back from Sphero.
00683     """
00684     self.send(self.pack_cmd(REQ['CMD_ROLL'],[self.clamp(speed,0,255), (heading>>8), (heading & 0xff), state]), response)
00685 
00686   def boost(self, time, heading, response):
00687     """
00688     This commands Sphero to meet the provided heading, disable
00689     stabilization and ramp the motors up to full-speed for a period of
00690     time. The Time parameter is the duration in tenths of a
00691     second. Setting it to zero enables constant boost until a Set
00692     Stabilization command is received.
00693 
00694     :param time: duration of boost in tenths of seconds.
00695     :param heading: the heading to travel while boosting.
00696     :param response: request response back from Sphero.
00697     """
00698     self.send(self.pack_cmd(REQ['CMD_BOOST'], [time, (heading>>8), (heading & 0xff)]), response)
00699 
00700   def set_raw_motor_values(self, l_mode, l_power, r_mode, r_power, response):
00701     """
00702     This allows you to take over one or both of the motor output
00703     values, instead of having the stabilization system control
00704     them. Each motor (left and right) requires a mode (see below) and
00705     a power value from 0- 255. This command will disable stabilization
00706     if both modes aren't "ignore" so you'll need to re-enable it via
00707     CID 02h once you're done.
00708 
00709     :param mode: 0x00 - off, 0x01 - forward, 0x02 - reverse, 0x03 -\
00710     brake, 0x04 - ignored.
00711     :param power: 0-255 scalar value (units?).
00712     """
00713     self.send(self.pack_cmd(REQ['CMD_RAW_MOTORS'], [l_mode, l_power, r_mode, r_power]), response)
00714 
00715   def send(self, data, response):
00716     """
00717     Packets are sent from Client -> Sphero in the following byte format::
00718 
00719       -------------------------------------------------------
00720       | SOP1 | SOP2 | DID | CID | SEQ | DLEN | <data> | CHK |
00721       -------------------------------------------------------
00722 
00723     * SOP1 - start packet 1 - Always 0xff. 
00724     * SOP2 - start packet 2 - Set to 0xff when an acknowledgement is\
00725       expected, 0xfe otherwise.    
00726     * DID - Device ID
00727     * CID - Command ID
00728     * SEQ - Sequence Number - This client field is echoed in the\
00729       response for all synchronous commands (and ignored by Sphero\
00730       when SOP2 = 0xfe)
00731     * DLEN - Data
00732     * Length - Number of bytes through the end of the packet.
00733     * <data>
00734     * CHK - Checksum - The modulo 256 sum of all the bytes from the\
00735       DID through the end of the data payload, bit inverted (1's\
00736       complement).
00737     """
00738     #compute the checksum
00739     #modulo 256 sum of data bit inverted
00740     checksum =~ sum(data) % 256
00741     #if expecting response back from the sphero
00742     if response:
00743       output = REQ['WITH_RESPONSE'] + data + [checksum]
00744     else:
00745       output = REQ['WITHOUT_RESPONSE'] + data + [checksum]
00746     #pack the msg
00747     msg = ''.join(struct.pack('B',x) for x in output)
00748     #send the msg
00749     with self._communication_lock:
00750       self.bt.send(msg)
00751 
00752   def run(self):
00753     # this is larger than any single packet
00754     self.recv(1024)
00755 
00756   def recv(self, num_bytes):
00757     '''
00758     Commands are acknowledged from the Sphero -> Client in the
00759     following format::
00760 
00761       -------------------------------------------------
00762       |SOP1 | SOP2 | MSRP | SEQ | DLEN | <data> | CHK |
00763       -------------------------------------------------
00764 
00765     * SOP1 - Start Packet 1 - Always 0xff.
00766     * SOP2 - Start Packet 2 - Set to 0xff when this is an\
00767       acknowledgement, 0xfe otherwise.
00768     * MSRP - Message Response - This is generated by the message\
00769       decoder of the virtual device.
00770     * SEQ - Sequence Number - Echoed to the client when this is a\
00771       direct message response (set to 00h when SOP2 = FEh)
00772     * DLEN - Data Length - The number of bytes following through the\
00773       end of the packet
00774     * <data>
00775     * CHK - Checksum - - The modulo 256 sum of all the bytes from the\
00776       DID through the end of the data payload, bit inverted (1's\
00777       complement)
00778 
00779     Asynchronous Packets are sent from Sphero -> Client in the
00780     following byte format::
00781 
00782       -------------------------------------------------------------
00783       |SOP1 | SOP2 | ID CODE | DLEN-MSB | DLEN-LSB | <data> | CHK |
00784       -------------------------------------------------------------
00785 
00786     * SOP1 - Start Packet 1 - Always 0xff.
00787     * SOP2 - Start Packet 2 - Set to 0xff when this is an
00788       acknowledgement, 0xfe otherwise.
00789     * ID CODE - ID Code - See the IDCODE dict
00790     * DLEN-MSB - Data Length MSB - The MSB number of bytes following\
00791       through the end of the packet
00792     * DLEN-LSB - Data Length LSB - The LSB number of bytes following\
00793       through the end of the packet
00794     * <data>
00795     * CHK - Checksum - - The modulo 256 sum of all the bytes from the\
00796       DID through the end of the data payload, bit inverted (1's\
00797       complement)
00798 
00799     '''
00800 
00801     while self.is_connected and not self.shutdown:
00802       with self._communication_lock:
00803         self.raw_data_buf += self.bt.recv(num_bytes)
00804       data = self.raw_data_buf
00805       while len(data)>5:
00806         if data[:2] == RECV['SYNC']:
00807           #print "got response packet"
00808           # response packet
00809           data_length = ord(data[4])
00810           if data_length+5 <= len(data):
00811             data_packet = data[:(5+data_length)]
00812             data = data[(5+data_length):]
00813           else:
00814             break
00815             #print "Response packet", self.data2hexstr(data_packet)
00816          
00817         elif data[:2] == RECV['ASYNC']:
00818           data_length = (ord(data[3])<<8)+ord(data[4])
00819           if data_length+5 <= len(data):
00820             data_packet = data[:(5+data_length)]
00821             data = data[(5+data_length):]
00822           else:
00823             # the remainder of the packet isn't long enough
00824             break
00825           if data_packet[2]==IDCODE['DATA_STRM'] and self._async_callback_dict.has_key(IDCODE['DATA_STRM']):
00826             self._async_callback_dict[IDCODE['DATA_STRM']](self.parse_data_strm(data_packet, data_length))
00827           elif data_packet[2]==IDCODE['COLLISION'] and self._async_callback_dict.has_key(IDCODE['COLLISION']):
00828             self._async_callback_dict[IDCODE['COLLISION']](self.parse_collision_detect(data_packet, data_length))
00829           elif data_packet[2]==IDCODE['PWR_NOTIFY'] and self._async_callback_dict.has_key(IDCODE['PWR_NOTIFY']):
00830             self._async_callback_dict[IDCODE['PWR_NOTIFY']](self.parse_pwr_notify(data_packet, data_length))
00831           else:
00832             print "got a packet that isn't streaming"
00833         else:
00834           raise RuntimeError("Bad SOF : " + self.data2hexstr(data))
00835       self.raw_data_buf=data
00836 
00837   def parse_pwr_notify(self, data, data_length):
00838     '''
00839     The data payload of the async message is 1h bytes long and
00840     formatted as follows::
00841 
00842       --------
00843       |State |
00844       --------
00845 
00846     The power state byte: 
00847       * 01h = Battery Charging, 
00848       * 02h = Battery OK,
00849       * 03h = Battery Low, 
00850       * 04h = Battery Critical
00851     '''
00852     return struct.unpack_from('B', ''.join(data[5:]))[0]
00853 
00854   def parse_collision_detect(self, data, data_length):
00855     '''
00856     The data payload of the async message is 10h bytes long and
00857     formatted as follows::
00858 
00859       -----------------------------------------------------------------
00860       |X | Y | Z | AXIS | xMagnitude | yMagnitude | Speed | Timestamp |
00861       -----------------------------------------------------------------
00862 
00863     * X, Y, Z - Impact components normalized as a signed 16-bit\
00864     value. Use these to determine the direction of collision event. If\
00865     you don't require this level of fidelity, the two Magnitude fields\
00866     encapsulate the same data in pre-processed format.
00867     * Axis - This bitfield specifies which axes had their trigger\
00868     thresholds exceeded to generate the event. Bit 0 (01h) signifies\
00869     the X axis and bit 1 (02h) the Y axis.
00870     * xMagnitude - This is the power that crossed the programming\
00871     threshold Xt + Xs.
00872     * yMagnitude - This is the power that crossed the programming\
00873     threshold Yt + Ys.
00874     * Speed - The speed of Sphero when the impact was detected.
00875     * Timestamp - The millisecond timer value at the time of impact;\
00876     refer to the documentation of CID 50h and 51h to make sense of\
00877     this value.
00878     '''
00879     output={}
00880     
00881     output['X'], output['Y'], output['Z'], output['Axis'], output['xMagnitude'], output['yMagnitude'], output['Speed'], output['Timestamp'] = struct.unpack_from('>hhhbhhbI', ''.join(data[5:]))
00882     return output
00883 
00884   def parse_data_strm(self, data, data_length):
00885     output={}
00886     for i in range((data_length-1)/2):
00887       unpack = struct.unpack_from('>h', ''.join(data[5+2*i:]))
00888       output[self.mask_list[i]] = unpack[0]
00889     #print self.mask_list
00890     #print output
00891     return output
00892 
00893 
00894 
00895   def disconnect(self):
00896     self.is_connected = False
00897     self.bt.close()
00898     return self.is_connected
00899 
00900 


sphero_driver
Author(s): Melonee Wise
autogenerated on Mon Oct 6 2014 07:45:28