Overview

The platform interface provides direct access to the physical (or simulated) robot, its various sensors and actuators, and its supplementary output systems (sound and light emitters). It is summarised in the diagram below.

Upstream

Frames from the two individual cameras (in the eyes), as well as frames interleaving audio from the twin microphones (in the ears), are delivered asynchronously as they become available (i.e. there are three asynchronous streams in total). Depending on conditions, the timing relationships amongst these frames, and between these frames and the synchronous data streams, may vary and are not predictable.

Cameras

ROS stream specification
stream descriptionraw RGB frames from twin camera eyes
topic nameplatform/caml, platform/camr
message typesensor_msgs/Image

Raw frames from each camera are delivered at a specified frame size and target frame rate. The defaults for these are 320×240 and 5 frames/sec. The actual frame rate achieved will be reduced automatically if there is insufficient light to expose the frame properly at the target rate. Since the two cameras may experience different lighting conditions, the frame rates of the two cameras may diverge under low light.

Camera frames are delivered by the platform in R5G6B5 format, and converted to R8G8B8 (i.e. standard RGB) by the bridge if it is in ROS mode. These raw frames can be compressed for transport in the usual way, by subscribing to a ROS topic of the form /miro/my_robot/platform/caml/compressed.

Microphones

ROS stream specification
stream descriptioninterleaved stereo samples from twin ear microphones
topic nameplatform/mics
message typemiro_msgs/platform_mics

Audio is recorded from the ear microphones at 20kHz and at 10-bit resolution. Samples are packaged into int16 containers and interleaved. A single on-board ADC samples both channels, so that the times of the samples are also inter-leaved (i.e. the underlying sampling rate is 40kHz, and the two channels are sampled in turn at that rate).

Audio is published on the ROS interface in a custom message container.

Sensors

ROS stream specification
stream descriptionsynchronous sensor data
topic nameplatform/sensors
message typemiro_msgs/platform_sensors

Data from all other platform sensors is packaged together into a single custom message and delivered synchronously (the "hi-rate" clock on MIRO runs at 50Hz, so this stream and other synchronous streams adopt this rate). Sensors served by this stream are interoceptive (battery voltage, temperature, linear accelerometers in head and body, body position odometry, mechanical joint state, and physical DIP switch state) and exteroceptive (sonar range, light levels, touch sensor binary states, and cliff sensors state).

Interoceptive sensors
battery_voltagemain battery voltage in volts
temperatureinternal temperature in celsius (approximate external temperature)
accel_headlinear acceleration measured in head in m/s2
accel_bodylinear acceleration measured in body in m/s2
odometryforward (linear.x) and rotational (angular.z) motion of body (other elements are zero)
joint_stateconfiguration in Radians of each of four kinematic joints: tilt, lift, yaw, and pitch (tilt is not implemented on current robots)
eyelid_closurescalar indicating closure of eyelids in [0.0, 1.0]
dip_state_physeach of bits 0 to 3 indicates state of one of the DIP switches on UC4
Exteroceptive sensors
sonar_rangerange to detected obstacle in metres (0.03m to 1.00m, or 0 to indicate "nothing detected")[1]
lightlight level between 0 and 255 on each of four sensors (front left, right, rear left, right)
touch_headbinary state of four touch sensors behind the ears
touch_bodybinary state of four touch sensors arrayed down the back
cliffstate of twin cliff sensors (left, right) in 0 (no surface detected) to 15 (surface definitely present)

This message, as many others, includes a reading from the embedded microsecond clock, time_usec, providing a high-precision indication of the time the message was assembled on the platform (delivery to the network adds an additional small latency). Relative timing of messages can be computed by comparing these timestamps.

[1] 0 indicates "nothing detected", which might be interpreted as "> 1.00m" or as "no data", depending on your application. Ranges out to 0.30m are most reliable, so for applications where reliability is most important, longer range detections may want to be reinterpreted as "> 0.30m" or as "no data".

State

ROS stream specification
stream descriptionsynchronous state data
topic nameplatform/state
message typemiro_msgs/platform_state

Platform state is also provided synchronously at the hi-rate, with a time_usec timestamp. Most of the fields will be of little interest most of the time; some may be of help in identifying a problem, should one occur.

P1 state
P1_releaseP1 release tag (release tag of MDK that was used to program P1).
P1_modeAlways zero in current implementation.
P1_error_codeZero if things are going well[2].
P1_R_signalsSome signals may be of interest to indicate P1 status (e.g. find MIRO_P1_R_LOW_BATT, and other signals, in miro_constants.h).
success_r, success_wIndividual bits are set on successful read (success_r) or write (success_w) to peripheral boards on the I2C bus. May be of use in identifying failed peripheral board.
seedUnsigned 32-bit seed generated from thermal noise in P1 at power on; may be used by higher processors as random seed, also.
 
P2 state
P2_releaseP2 release tag (release tag of MDK that was used to program P2).
serialSerial number programmed stored in embedded FLASH for this robot (see set_P2_serial.sh at mdk/bin/am335x to set).
P2_modeReflects current P2 mode.
P2C_R_signalsSignals from MIRO_P2C_R object on the native interface (see miro_constants.h).
P2L_R_signalsSignals from MIRO_P2L_R object on the native interface (see miro_constants.h).
P2U_R_signalsSignals from MIRO_P2U_R object on the native interface (see miro_constants.h).
num_free_stream_bufNumber of free stream buffers available in P2 to accept streaming audio frames.
msg_id_of_last_stream_buf_recvMessage identified of last streaming audio frame received in P2, for ease of interpretation of num_free_stream_buf in the presence of loop latency.
rtc_hrs, etc.State of real-time clock in P2; rtc_skew indicates accumulated skew from circadian model, that will cause a clock shift once it becomes large enough.
 
Bridge state
number_of_loaded_soundsNumber of sounds loaded by miro_bridge; bridge will respond to this many sound identifiers to begin streaming.

[2] P1 error code 1 is I2C_BUSY. If this code is returned repeatedly (usually accompanied by warbling alarm sound) the I2C bus is damaged. Try disconnecting I2C cables until the code is cleared, to identify which cable or board is faulty.

Downstream

Control

ROS stream specification
stream descriptionsynchronous control data
topic nameplatform/control
message typemiro_msgs/platform_control

Downstream control signals can be processed at the hi-rate (50Hz). However, if they are delivered more slowly, they are held over (for up to one second) to maintain a stable control signal to the platform. It is a choice for the higher-level controller, therefore, at what rate to deliver this stream—a rate of 10Hz, for instance, may be adequate for some applications.

If hi-rate control messages are being sent on both Platform Interface and Core Interface, both messages should set flags FLAG_SYNC_PLATFORM and FLAG_SYNC_CORE. In this case, the messages will be assembled and sent down to the platform in the same control packet, ensuring synchronicity of the two control streams.
Drive kinematic DOFs
body_velImmediate command for forward (linear.x) and rotational (angular.z) motion of body (other elements of the object are ignored).

To control individual wheel speeds, see example below.
body_configCommanded configuration in Radians of each of four kinematic joints: tilt, lift, yaw, and pitch (tilt is not implemented on current robots).
body_config_speedSpeed in Radians/second to approach commanded position, for each joint (-1.0 means "infinite", i.e. get there as quickly as possible).
body_moveThis field, and the associated body_move_flags field, are used to initiate a locally-controlled body move using Park & Kuipers 2011 (ICRA) controller.
 
Drive cosmetic DOFs
tailTail control (-1.0 is maximally drooped, 0.0 is neutral, 1.0 is maximally wagging).
ear_rotateEar rotation for two ears, individually, from 0.0 (forwards-facing) to 1.0 (laterally-facing).
eyelid_closureDoes what it says on the tin, from 0.0 (open) to 1.0 (closed).
blink_timeSend a single positive value to start a blink of duration as indicated in 20msec periods (send a negative value to make it a double blink instead).
lights_*A monochromatic lighting pattern generator operates in P1; these parameters can enable and control it, if the user prefers not to control the lights individually (that facility is not currently available on the ROS interface).
sound_index_P1Pulse a positive value in this field to play one of the pre-loaded P1 sounds (values up to 30 are available, at time of writing; unavailable values have no effect).
sound_index_P2Pulse a positive value in this field to play one of the pre-loaded P2 sounds (values up to 23 are available, at time of writing; unavailable values have no effect).

The following Python example shows how to control the speed of the individual wheels directly, through the body_vel interface, if required.

control_wheel_speeds.py
# desired wheel speeds (mm/sec) wheel_speed_l = -100 wheel_speed_r = 50 # constants are in share/miro_constants/miro.py (or include/miro_platform.h) dr = (wheel_speed_l + wheel_speed_r) / 2.0 dtheta = (wheel_speed_r - wheel_speed_l) / MIRO_WHEEL_TRACK_MM # send q = platform_control() q.body_vel = Twist() q.body_vel.linear.x = dr; q.body_vel.angular.z = dtheta;

Stream

Audio can be streamed into the USB link to drive the on-board speaker with any mono signal, as required. This provides more generality when the on-board sound synthesizer or pre-recorded samples are not appropriate. Streaming audio frames can be delivered in asynchronous fashion. So long as P2 does not run out of buffered frames, the stream is reassembled there before synchronous delivery to the on-board speaker through P1.

The streaming source is usually miro_bridge—when starting miro_bridge, the argument sound can be passed to load a library of sound samples into memory. Streaming of one of these sound samples is then started by sending the bridge_config message to the bridge and setting field sound_index_P3. The native streaming interface is not currently exposed to the network, but can be accessed from on-board if required.

Config

ROS stream specification
stream descriptionconfiguration data
topic nameplatform/config
message typemiro_msgs/platform_config

This asynchronous stream permits updating the platform configuration at run-time.

Cameras
frame_sizeEither 128, 192 or 320 (for 128×96, 192×144 or 320×240).
frame_rateAny frame rate can be requested—the nearest available rate will be configured.
Since the platform configuration is stored in RAM in the embedded system, a configuration passed will persist until MIRO is power cycled, and then be restored to default.