Overview

The ROS (Robot Operating System) interface provides access to the physical (or simulated) robot, its various sensors and actuators, and its supplementary output systems (sound and light emitters). A complete list of topics is given below.

ROS is not a secure network protocol—unauthorized access to data published from your robot is possible. See the Information Security section of the Owner's Guide before continuing.
Before you can use this interface you must use MiRoapp to connect your robot to a network.

General information

Topic names are based on the Robot Name which can be set using MiRoapp. The default robot name, for example, is miro. In this case, sensor topics will be under /miro/sensors and control topics under /miro/control. Below, we omit the robot name from the topic names in the topic list.

All topics are published at 50Hz except camera and microphone topics, which arrive asynchronously. Downstream control signals can be processed at up to 50Hz, but receivers will behave coherently at signalling rates down to 10Hz. Often, clients will find it sufficient to control at 10Hz even if they receive data at 50Hz.

This interface uses standard message types for most topics, favouring the widest set of clients. All 50Hz sensor data is packaged into one custom message at sensors/package. Clients that are able to work with custom message types will usually find it convenient to subscribe to this topic to receive all the 50Hz data in one package. In addition, the sensors/battery topic uses the ROS Kinetic version of BatteryState, which is packaged in miro_msg so that it is available to users of other ROS versions.

For examples of how to exchange data with these topics, see the Examples at ~/mdk/bin/shared (most if not all topics are exercised by ~/mdk/bin/shared/client_gui.py, but some more specific clients are present, and are referenced in the tables below).
You can use this interface from any development language that supports ROS—if using C/C++, you will find the headers you need at ~/mdk/include and ~/mdk/catkin_ws/install/include, and a client template at ~/mdk/share/src/client_template.

Interoceptive sensors at 50Hz

sensors/wheel_speed_cmd

Message type: std_msgs/Float32MultiArray.

The commanded wheel speed sent down to the motor controllers after all operations have completed (m/s) in the order [LEFT, RIGHT].

sensors/wheel_speed_opto

Message type: std_msgs/Float32MultiArray.

The wheel speeds measured using the opto encoders (m/s) in the order [LEFT, RIGHT].

sensors/wheel_speed_back_emf

Message type: std_msgs/Float32MultiArray.

The wheel speeds measured using motor back EMF (m/s) in the order [LEFT, RIGHT].

sensors/wheel_effort_pwm

Message type: std_msgs/Float32MultiArray.

The wheel drive effort (motor current) in normalised units in the order [LEFT, RIGHT]. The actual motor current delivered is constrained to lie in [-1.0, +1.0], but the values published here can exceed this interval if the wheel controller asked for more current (which could not physically be delivered).

sensors/body_vel

Message type: geometry_msgs/TwistStamped.

Body velocity computed from sensors/wheel_speed_opto (m/s and Rad/s).

The following Python example shows how to recover the speed of the individual wheels from sensors/body_vel, if required.

recover_wheel_speeds.py
import miro2 as miro # receive command velocity from sensors/body_vel (m/sec, Rad/sec) dr = msg.twist.linear.x dtheta = msg.twist.angular.z # convert to wheel speed (m/sec) wheel_speed = miro.lib.cmd_vel2wheel_speed(dr, dtheta)

sensors/odom

Message type: nav_msgs/Odometry.

In twist, the same values as sensors/body_vel but packaged differently. In pose, an integrating estimate of the robot pose derived as the naive integration of the data in twist suitable for use as input to the standard ROS navigation stack.

sensors/kinematic_joints

Message type: sensor_msgs/JointState.

Internal DOF configuration (Rad) in the order [TILT, LIFT, YAW, PITCH] (see Geometry).

sensors/battery

Message type: miro2_msg/BatteryState (sensor_msgs/BatteryState from ROS Kinetic).

Battery voltage (V).

sensors/dip

Message type: std_msgs/UInt16.

State of internal DIP switches in a bit array, if fitted (otherwise reads zero).

sensors/imu_body

Message type: sensor_msgs/Imu.

Acceleration vector measured in body (m/s).

sensors/imu_head

Message type: sensor_msgs/Imu.

Acceleration vector measured in head (m/s).

Exteroceptive sensors at 50Hz

sensors/light

Message type: std_msgs/Float32MultiArray.

Level at each of the four light sensors in normalised units in the order [FRONT LEFT, RIGHT, REAR LEFT, RIGHT]. A value of 0.0 indicates total darkness, and a value of 1.0 indicates the sensor is under strong illumination.

sensors/touch_body

Message type: std_msgs/UInt16.

Binary state of body touch sensors in a bit array.

sensors/touch_head

Message type: std_msgs/UInt16.

Binary state of head touch sensors in a bit array.

sensors/cliff

Message type: std_msgs/Float32MultiArray.

Reading from each of the two cliff sensors in normalised units in the order [LEFT, RIGHT]. A value of 1.0 strongly indicates that a surface is present, whilst a value of 0.0 indicates no evidence that a surface is present. Actual values returned will depend on physical surface characteristics.

sensors/sonar

Message type: sensor_msgs/Range.

Range to strongest sonar reflector (m). Normal values are in the interval [0.03m, 1.0m). A value of 0.0m indicates that an echo was received at closer than 0.03m, which may not be reliable data. A value of infinity indicates that no echo was received.

Packaged sensors at 50Hz

sensors/package

Message type: miro2_msg/sensors_package.

All the 50Hz sensors (above) packaged into one topic.

Asynchronous sensors

sensors/mics

Message type: std_msgs/Int16MultiArray.

Block of interleaved samples from four microphones in the order [LEFT, RIGHT, CENTRE, TAIL] (arbitrary units packaged in an int16, sample rate is 20kHz, packages arrive at around 40Hz in default configuration).

sensors/caml

Message type: sensor_msgs/Image.

Frames from the left eye camera (sample rate is variable, see control/command).

sensors/camr

Message type: sensor_msgs/Image.

Frames from the right eye camera (sample rate matches sensors/caml).

Simulator only

sensors/body_pose

Message type: geometry_msgs/Pose2D.

Pose of the robot body (FOOT frame) in the WORLD frame (m and Rad). This is not computed by the physical robot, but is published by the simulator (at 50Hz) to aid in development.

To obtain an estimate of this pose when using the physical robot, integrate sensors/body_vel (this estimate will suffer from integral error, a well-studied problem in robotics).

sensors/overhead

Message type: sensor_msgs/Image.

Frames from the overhead camera (sample rate matches sensors/caml). Only available in the simulator, if enabled.

Platform state

sensors/log

Message type: std_msgs/String.

Log information from firmware and from bridge is generated here; used for diagnostics.

sensors/flags

Message type: std_msgs/UInt32.

Flags word indicating current state of platform (see Constants, flags for this topic are prefixed PLATFORM_U).

sensors/stream

Message type: std_msgs/UInt16MultiArray.

State of audio stream buffer in the format [buffer_space, buffer_total] (bytes).

A client may publish up to (buffer_total - buffer_space) bytes to control/stream after receiving this signal without overflowing the stream buffer. However, a shorter streaming latency is achieved if the client does not stuff the buffer any more than necessary to maintain continuous playback.

See ~/mdk/bin/shared/client_stream.py for an example of using this topic.

Actuators

control/cmd_vel

Message type: geometry_msgs/TwistStamped.

Commanded body velocity (complements sensors/body_vel).

The following Python example shows how to control the speed of the individual wheels through control/cmd_vel, if required.

control_wheel_speeds.py
import miro2 as miro # desired wheel speed (m/sec) wheel_speed = [-0.1, 0.05] # convert to command velocity (m/sec, Rad/sec) (dr, dtheta) = miro.lib.wheel_speed2cmd_vel(wheel_speed) # construct message to send to control/cmd_vel msg = TwistStamped() msg.twist.linear.x = dr; msg.twist.angular.z = dtheta;

control/kinematic_joints

Message type: sensor_msgs/JointState of length 4.

Commanded internal DOF configuration (complements sensors/kinematic_joints).

control/cosmetic_joints

Message type: std_msgs/FloatMultiArray of length 6.

Commanded configuration of cosmetic joints (normalised). Six joints are commanded in the order [droop, wag, eyel, eyer, earl, earr].

There is no sensory feedback for cosmetic joints.

Supplementary output systems

control/illum

Message type: std_msgs/UInt32MultiArray of length 6.

Commanded pattern for the six illumination LEDs in the order [Left Front, Middle, Rear, Right Front, Middle, Rear]. Each element is an bRGB word where the "b" is a brightness channel that scales the other three channels (i.e. it is as an independent brightness control).

control/tone

Message type: std_msgs/UInt16MultiArray of length 3.

The three elements are [frequency, volume, duration] of a tone that will be produced by the on-board speaker. Frequency is in Hertz (values between 50 and 2000 are accepted), volume is in 0 to 255, and duration is in platform ticks (20ms periods).

control/stream

Message type: std_msgs/Int16MultiArray of maximum length 4000 bytes.

See ~/mdk/bin/shared/client_stream.py for an example of using this topic.

Platform configuration

control/flags

Message type: std_msgs/UInt32.

Flags word controlling current state of platform (see Constants, flags for this topic are prefixed PLATFORM_D).

Controllers should usually send this topic just once at the beginning of their execution—see the example client_template for an example of this (search for "--no-cliff").

If you include the flag PLATFORM_D_FLAG_PERSISTENT, the passed flags will be retained until reboot, or until you send a new value. If not, they will expire whenever no motor control commands (specifically, control/cmd_vel, control/kinematic_joints, or control/cosmetic_joints) have been received for a period of one second, at which point they will reset to the configured bridge flags.

This topic is an interface to temporarily override the bridge flags—configure the bridge flags directly to permanently change your robot's default flag set.

control/command

Message type: std_msgs/String.

String command to be interpreted by the bridge in changing the operational state of the platform. Multiple commands can be included in a single string, separated by semicolons.

frame=<frame_size>@<frame_rate>
Change camera frame size and rate (<frame_size> can be any of: 180s, 180w, 240s, 360s, 360w, 720s, 720w; <frame_rate> can be any value but will be constrained between 1 and the maximum frame rate available at the specified resolution). Resolutions are specified as frame height with s for standard aspect ratio (4:3) and w for wide (16:9).
jpeg=<jpeg_quality_percent>
Change JPEG encoder quality (values between 10 and 90 are accepted, but very high values used with high frame rates may overload frame delivery bandwidth and lead to dropped frames).