sphero.py provides a simple ROS wrapper for the sphero_driver.
The Python API for the underlying Sphero driver.
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
This is a developers-only command to clear the various system counters described in the level 2 diag.
Parameters: | response – request response back from Sphero. |
---|
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.
Parameters: |
|
---|
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.
This returns the Bluetooth auto reconnect values as defined in the Set Auto Reconnect command.
Parameters: | response – request response back from Sphero. |
---|
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.
Parameters: | response – request response back from Sphero. |
---|
This returns the current power state and some additional parameters to the Client.
Parameters: | response – request response back from Sphero. |
---|
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).
Parameters: | response – request response back from Sphero. |
---|
The Get Versioning command returns a whole slew of software and hardware information.
Parameters: | response – request response back from Sphero. |
---|
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.
Parameters: |
|
---|
The data payload of the async message is 10h bytes long and formatted as follows:
-----------------------------------------------------------------
|X | Y | Z | AXIS | xMagnitude | yMagnitude | Speed | Timestamp |
-----------------------------------------------------------------
The data payload of the async message is 1h bytes long and formatted as follows:
--------
|State |
--------
The Ping command is used to verify both a solid data link with the Client and that Sphero is awake and dispatching commands.
Parameters: | response – request response back from Sphero. |
---|
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 () 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 (). Just before the transmit engine streams it into the Bluetooth module, the Sphero Tx time value () is filled in. If the Client then records the time at which the response is received () the relevant time segments can be computed from the four time stamps ():
Parameters: |
|
---|
Commands are acknowledged from the Sphero -> Client in the following format:
-------------------------------------------------
|SOP1 | SOP2 | MSRP | SEQ | DLEN | <data> | CHK |
-------------------------------------------------
Asynchronous Packets are sent from Sphero -> Client in the following byte format:
-------------------------------------------------------------
|SOP1 | SOP2 | ID CODE | DLEN-MSB | DLEN-LSB | <data> | CHK |
-------------------------------------------------------------
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.
Parameters: |
|
---|
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.
Parameters: | response – request response back from Sphero. |
---|
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.
Parameters: | response – request response back from Sphero. |
---|
Packets are sent from Client -> Sphero in the following byte format:
-------------------------------------------------------
| SOP1 | SOP2 | DID | CID | SEQ | DLEN | <data> | CHK |
-------------------------------------------------------
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.
Parameters: |
|
---|
This allows you to write a 32 byte block of data from the configuration block that is set aside for exclusive use by applications.
Parameters: |
|
---|
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.
Parameters: |
|
---|
This allows you to control the brightness of the back LED. The value does not persist across power cycles.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|
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.
Parameters: |
|
---|