Definition at line 221 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.__init__ | ( | self, | |
target_name = 'Sphero' |
|||
) |
Definition at line 223 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.add_async_callback | ( | self, | |
callback_type, | |||
callback | |||
) |
Definition at line 269 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.add_sync_callback | ( | self, | |
callback_type, | |||
callback | |||
) |
Definition at line 275 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.assign_counter_value | ( | self, | |
counter, | |||
response | |||
) |
Sphero contains a 32-bit counter that increments every millisecond when it's not in the Idle state. It has no absolute meaning and is reset for various reasons. This command assigns the counter a specific value for subsequent sampling. :param counter: value to set the counter to. :param response: request response back from Sphero.
Definition at line 422 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.boost | ( | self, | |
time, | |||
heading, | |||
response | |||
) |
This commands Sphero to meet the provided heading, disable stabilization and ramp the motors up to full-speed for a period of time. The Time parameter is the duration in tenths of a second. Setting it to zero enables constant boost until a Set Stabilization command is received. :param time: duration of boost in tenths of seconds. :param heading: the heading to travel while boosting. :param response: request response back from Sphero.
Definition at line 686 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.clamp | ( | self, | |
n, | |||
minn, | |||
maxn | |||
) |
Definition at line 281 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.clear_counters | ( | self, | |
response | |||
) |
This is a developers-only command to clear the various system counters described in the level 2 diag. :param response: request response back from Sphero.
Definition at line 413 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.config_collision_detect | ( | self, | |
method, | |||
Xt, | |||
Xspd, | |||
Yt, | |||
Yspd, | |||
ignore_time, | |||
response | |||
) |
This command either enables or disables asynchronous message generation when a collision is detected.The Ignore Time parameter disables collision detection for a period of time after the async message is generated, preventing message overload to the client. The value is in 10 millisecond increments. :param method: Detection method type to use. Currently the only\ method supported is 01h. Use 00h to completely disable this\ service. :param Xt, Yt: An 8-bit settable threshold for the X (left/right)\ and Y (front/back) axes of Sphero. A value of 00h disables the\ contribution of that axis. :param Xspd,Yspd: An 8-bit settable speed value for the X and Y\ axes. This setting is ranged by the speed, then added to Xt, Yt to\ generate the final threshold value. :param ignore_time: An 8-bit post-collision dead time to prevent\ retriggering; specified in 10ms increments.
Definition at line 612 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.connect | ( | self | ) |
Definition at line 239 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.create_mask_list | ( | self, | |
mask1, | |||
mask2 | |||
) |
Definition at line 257 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.data2hexstr | ( | self, | |
data | |||
) |
Definition at line 254 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.disconnect | ( | self | ) |
Definition at line 895 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.get_app_config_blk | ( | self, | |
response | |||
) |
This allows you to retrieve the application configuration block\ that is set aside for exclusive use by applications. :param response: request response back from Sphero.
Definition at line 516 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.get_auto_reconnect | ( | self, | |
response | |||
) |
This returns the Bluetooth auto reconnect values as defined in the Set Auto Reconnect command. :param response: request response back from Sphero.
Definition at line 345 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.get_bt_name | ( | self, | |
response | |||
) |
This returns the textual name (in ASCII) that the Bluetooth module advertises. It also returns the BTA Bluetooth Address or MAC ID for this device. Both values are returned in ASCII and have field widths of 16 characters, with unused trailing characters set to 00h. :param response: request response back from Sphero.
Definition at line 315 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.get_power_state | ( | self, | |
response | |||
) |
This returns the current power state and some additional parameters to the Client. :param response: request response back from Sphero.
Definition at line 354 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.get_rgb_led | ( | self, | |
response | |||
) |
This retrieves the "user LED color" which is stored in the config block (which may or may not be actively driven to the RGB LED). :param response: request response back from Sphero.
Definition at line 660 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.get_version | ( | self, | |
response | |||
) |
The Get Versioning command returns a whole slew of software and hardware information. :param response: request response back from Sphero.
Definition at line 293 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.go_to_sleep | ( | self, | |
time, | |||
macro, | |||
response | |||
) |
This puts Sphero to sleep immediately with two parameters: the first is the number of seconds after which it will automatically re-awaken. If set to zero, this feature is disabled. If non-zero then the MACRO parameter allows an optional system macro to be run upon wakeup. If this is set to zero, no macro is executed. :param time: number of seconds wait before auto re-awake. :param macro: macro number to run when re-awakened. :param response: request response back from Sphero.
Definition at line 376 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.inc_seq | ( | self | ) |
Definition at line 244 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.pack_cmd | ( | self, | |
req, | |||
cmd | |||
) |
Definition at line 249 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.parse_collision_detect | ( | self, | |
data, | |||
data_length | |||
) |
The data payload of the async message is 10h bytes long and formatted as follows:: ----------------------------------------------------------------- |X | Y | Z | AXIS | xMagnitude | yMagnitude | Speed | Timestamp | ----------------------------------------------------------------- * X, Y, Z - Impact components normalized as a signed 16-bit\ value. Use these to determine the direction of collision event. If\ you don't require this level of fidelity, the two Magnitude fields\ encapsulate the same data in pre-processed format. * Axis - This bitfield specifies which axes had their trigger\ thresholds exceeded to generate the event. Bit 0 (01h) signifies\ the X axis and bit 1 (02h) the Y axis. * xMagnitude - This is the power that crossed the programming\ threshold Xt + Xs. * yMagnitude - This is the power that crossed the programming\ threshold Yt + Ys. * Speed - The speed of Sphero when the impact was detected. * Timestamp - The millisecond timer value at the time of impact;\ refer to the documentation of CID 50h and 51h to make sense of\ this value.
Definition at line 854 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.parse_data_strm | ( | self, | |
data, | |||
data_length | |||
) |
Definition at line 884 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.parse_pwr_notify | ( | self, | |
data, | |||
data_length | |||
) |
The data payload of the async message is 1h bytes long and formatted as follows:: -------- |State | -------- The power state byte: * 01h = Battery Charging, * 02h = Battery OK, * 03h = Battery Low, * 04h = Battery Critical
Definition at line 837 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.ping | ( | self, | |
response | |||
) |
The Ping command is used to verify both a solid data link with the Client and that Sphero is awake and dispatching commands. :param response: request response back from Sphero.
Definition at line 284 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.poll_packet_times | ( | self, | |
time, | |||
response | |||
) |
This command helps the Client application profile the transmission and processing latencies in Sphero so that a relative synchronization of timebases can be performed. It allows the Client to reconcile time stamped messages from Sphero to its own time stamped events. The scheme is as follows: the Client sends the command with the Client Tx time (:math:`T_{1}`) filled in. Upon receipt of the packet, the command processor in Sphero copies that time into the response packet and places the current value of the millisecond counter into the Sphero Rx time field (:math:`T_{2}`). Just before the transmit engine streams it into the Bluetooth module, the Sphero Tx time value (:math:`T_{3}`) is filled in. If the Client then records the time at which the response is received (:math:`T_{4}`) the relevant time segments can be computed from the four time stamps (:math:`T_{1}, T_{2}, T_{3}, T_{4}`): * The value offset represents the maximum-likelihood time offset\ of the Client clock to Sphero's system clock. * offset :math:`= 1/2*[(T_{2} - T_{1}) + (T_{3} - T_{4})]` * The value delay represents the round-trip delay between the\ Client and Sphero: * delay :math:`= (T_{4} - T_{1}) - (T_{3} - T_{2})` :param time: client Tx time. :param response: request response back from Sphero.
Definition at line 434 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.recv | ( | self, | |
num_bytes | |||
) |
Commands are acknowledged from the Sphero -> Client in the following format:: ------------------------------------------------- |SOP1 | SOP2 | MSRP | SEQ | DLEN | <data> | CHK | ------------------------------------------------- * SOP1 - Start Packet 1 - Always 0xff. * SOP2 - Start Packet 2 - Set to 0xff when this is an\ acknowledgement, 0xfe otherwise. * MSRP - Message Response - This is generated by the message\ decoder of the virtual device. * SEQ - Sequence Number - Echoed to the client when this is a\ direct message response (set to 00h when SOP2 = FEh) * DLEN - Data Length - The number of bytes following through the\ end of the packet * <data> * CHK - Checksum - - The modulo 256 sum of all the bytes from the\ DID through the end of the data payload, bit inverted (1's\ complement) Asynchronous Packets are sent from Sphero -> Client in the following byte format:: ------------------------------------------------------------- |SOP1 | SOP2 | ID CODE | DLEN-MSB | DLEN-LSB | <data> | CHK | ------------------------------------------------------------- * SOP1 - Start Packet 1 - Always 0xff. * SOP2 - Start Packet 2 - Set to 0xff when this is an acknowledgement, 0xfe otherwise. * ID CODE - ID Code - See the IDCODE dict * DLEN-MSB - Data Length MSB - The MSB number of bytes following\ through the end of the packet * DLEN-LSB - Data Length LSB - The LSB number of bytes following\ through the end of the packet * <data> * CHK - Checksum - - The modulo 256 sum of all the bytes from the\ DID through the end of the data payload, bit inverted (1's\ complement)
Definition at line 756 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.remove_async_callback | ( | self, | |
callback_type | |||
) |
Definition at line 272 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.remove_sync_callback | ( | self, | |
callback_type | |||
) |
Definition at line 278 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.roll | ( | self, | |
speed, | |||
heading, | |||
state, | |||
response | |||
) |
This commands Sphero to roll along the provided vector. Both a speed and a heading are required; the latter is considered relative to the last calibrated direction. A state Boolean is also provided (on or off). The client convention for heading follows the 360 degrees on a circle, relative to the ball: 0 is straight ahead, 90 is to the right, 180 is back and 270 is to the left. The valid range is 0..359. :param speed: 0-255 value representing 0-max speed of the sphero. :param heading: heading in degrees from 0 to 359. :param state: 00h for off (braking) and 01h for on (driving). :param response: request response back from Sphero.
Definition at line 669 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.run | ( | self | ) |
Definition at line 752 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.run_l1_diags | ( | self, | |
response | |||
) |
This is a developer-level command to help diagnose aberrant behavior. Most system counters, process flags, and system states are decoded into human readable ASCII. There are two responses to this command: a Simple Response followed by a large async message containing the results of the diagnostic tests. :param response: request response back from Sphero.
Definition at line 390 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.run_l2_diags | ( | self, | |
response | |||
) |
This is a developers-only command to help diagnose aberrant behavior. It is much less impactful than the Level 1 command as it doesn't interfere with the current operation it simply returns a current set of statistics to the client. :param response: request response back from Sphero.
Definition at line 402 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.send | ( | self, | |
data, | |||
response | |||
) |
Packets are sent from Client -> Sphero in the following byte format:: ------------------------------------------------------- | SOP1 | SOP2 | DID | CID | SEQ | DLEN | <data> | CHK | ------------------------------------------------------- * SOP1 - start packet 1 - Always 0xff. * SOP2 - start packet 2 - Set to 0xff when an acknowledgement is\ expected, 0xfe otherwise. * DID - Device ID * CID - Command ID * SEQ - Sequence Number - This client field is echoed in the\ response for all synchronous commands (and ignored by Sphero\ when SOP2 = 0xfe) * DLEN - Data * Length - Number of bytes through the end of the packet. * <data> * CHK - Checksum - The modulo 256 sum of all the bytes from the\ DID through the end of the data payload, bit inverted (1's\ complement).
Definition at line 715 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_all_data_strm | ( | self, | |
sample_div, | |||
sample_frames, | |||
pcnt, | |||
response | |||
) |
Helper function to add all the data to the data strm mask, so that the user doesn't have to set the data strm manually. :param sample_div: divisor of the maximum sensor sampling rate. :param sample_frames: number of sample frames emitted per packet. :param pcnt: packet count (set to 0 for unlimited streaming). :param response: request response back from Sphero.
Definition at line 594 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_app_config_blk | ( | self, | |
app_data, | |||
response | |||
) |
This allows you to write a 32 byte block of data from the configuration block that is set aside for exclusive use by applications. :param app_data: block set aside for application. :param response: request response back from Sphero.
Definition at line 505 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_auto_reconnect | ( | self, | |
enable, | |||
time, | |||
response | |||
) |
This configures the control of the Bluetooth module in its attempt to automatically reconnect with the last iPhone device. This is a courtesy behavior since the iPhone Bluetooth stack doesn't initiate automatic reconnection on its own. The two parameters are simple: flag = 00h to disable or 01h to enable, and time = the number of seconds after power-up in which to enable auto reconnect mode. For example, if time = 30 then the module will be attempt reconnecting 30 seconds after waking up. :param enable: 00h to disable or 01h to enable auto reconnecting. :param time: the number of seconds after power-up in which to\ enable auto reconnect mode :param response: request response back from Sphero.
Definition at line 327 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_back_led | ( | self, | |
brightness, | |||
response | |||
) |
This allows you to control the brightness of the back LED. The value does not persist across power cycles. :param brightness: 0-255, off-on (the blue LED on hemisphere of the Sphero). :param response: request response back from Sphero.
Definition at line 650 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_data_strm | ( | self, | |
sample_div, | |||
sample_frames, | |||
sample_mask1, | |||
pcnt, | |||
sample_mask2, | |||
response | |||
) |
Currently the control system runs at 400Hz and because it's pretty unlikely you will want to see data at that rate, N allows you to divide that down. sample_div = 2 yields data samples at 200Hz, sample_div = 10, 40Hz, etc. Every data sample consists of a "frame" made up of the individual sensor values as defined by the sample_mask. The sample_frames value defines how many frames to collect in memory before the packet is emitted. In this sense, it controls the latency of the data you receive. Increasing sample_div and the number of bits set in sample_mask drive the required throughput. You should experiment with different values of sample_div, sample_frames and sample_mask to see what works best for you. :param sample_div: divisor of the maximum sensor sampling rate. :param sample_frames: number of sample frames emitted per packet. :param sample_mask1: bitwise selector of data sources to stream. :param pcnt: packet count (set to 0 for unlimited streaming). :param response: request response back from Sphero.
Definition at line 524 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_device_name | ( | self, | |
name, | |||
response | |||
) |
This assigned name is held internally and produced as part of the Get Bluetooth Info service below. Names are clipped at 48 characters in length to support UTF-8 sequences; you can send something longer but the extra will be discarded. This field defaults to the Bluetooth advertising name. :param name: 48 character name. :param response: request response back from Sphero.
Definition at line 302 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_filtered_data_strm | ( | self, | |
sample_div, | |||
sample_frames, | |||
pcnt, | |||
response | |||
) |
Helper function to add all the filtered data to the data strm mask, so that the user doesn't have to set the data strm manually. :param sample_div: divisor of the maximum sensor sampling rate. :param sample_frames: number of sample frames emitted per packet. :param pcnt: packet count (set to 0 for unlimited streaming). :param response: request response back from Sphero.
Definition at line 555 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_heading | ( | self, | |
heading, | |||
response | |||
) |
This allows the client to adjust the orientation of Sphero by commanding a new reference heading in degrees, which ranges from 0 to 359. You will see the ball respond immediately to this command if stabilization is enabled. :param heading: heading in degrees from 0 to 359 (motion will be\ shortest angular distance to heading command) :param response: request response back from Sphero.
Definition at line 465 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_power_notify | ( | self, | |
enable, | |||
response | |||
) |
This enables Sphero to asynchronously notify the Client periodically with the power state or immediately when the power manager detects a state change. Timed notifications arrive every 10 seconds until they're explicitly disabled or Sphero is unpaired. The flag is as you would expect, 00h to disable and 01h to enable. :param enable: 00h to disable and 01h to enable power notifications. :param response: request response back from Sphero.
Definition at line 363 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_raw_data_strm | ( | self, | |
sample_div, | |||
sample_frames, | |||
pcnt, | |||
response | |||
) |
Helper function to add all the raw data to the data strm mask, so that the user doesn't have to set the data strm manually. :param sample_div: divisor of the maximum sensor sampling rate. :param sample_frames: number of sample frames emitted per packet. :param pcnt: packet count (set to 0 for unlimited streaming). :param response: request response back from Sphero.
Definition at line 574 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_raw_motor_values | ( | self, | |
l_mode, | |||
l_power, | |||
r_mode, | |||
r_power, | |||
response | |||
) |
This allows you to take over one or both of the motor output values, instead of having the stabilization system control them. Each motor (left and right) requires a mode (see below) and a power value from 0- 255. This command will disable stabilization if both modes aren't "ignore" so you'll need to re-enable it via CID 02h once you're done. :param mode: 0x00 - off, 0x01 - forward, 0x02 - reverse, 0x03 -\ brake, 0x04 - ignored. :param power: 0-255 scalar value (units?).
Definition at line 700 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_rgb_led | ( | self, | |
red, | |||
green, | |||
blue, | |||
save, | |||
response | |||
) |
This allows you to set the RGB LED color. The composite value is stored as the "application LED color" and immediately driven to the LED (if not overridden by a macro or orbBasic operation). If FLAG is true, the value is also saved as the "user LED color" which persists across power cycles and is rendered in the gap between an application connecting and sending this command. :param red: red color value. :param green: green color value. :param blue: blue color value. :param save: 01h for save (color is saved as "user LED color").
Definition at line 634 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_rotation_rate | ( | self, | |
rate, | |||
response | |||
) |
This allows you to control the rotation rate that Sphero will use to meet new heading commands. The commanded value is in units of 0.784 degrees/sec. So, setting a value of c8h will set the rotation rate to 157 degrees/sec. A value of 255 jumps to the maximum and a value of 1 is the minimum. :param rate: rotation rate in units of 0.784degrees/sec (setting\ this value will not cause the device to move only set the rate it\ will move in other funcation calls). :param response: request response back from Sphero.
Definition at line 490 of file sphero_driver.py.
def sphero_driver.sphero_driver.Sphero.set_stablization | ( | self, | |
enable, | |||
response | |||
) |
This turns on or off the internal stabilization of Sphero, in which the IMU is used to match the ball's orientation to its various set points. The flag value is as you would expect, 00h for off and 01h for on. :param enable: 00h for off and 01h for on (on by default). :param response: request response back from Sphero.
Definition at line 478 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 257 of file sphero_driver.py.
Definition at line 257 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.
Definition at line 223 of file sphero_driver.py.