Overview
MIRO's standard
interface is intended to be as compliant as possible with community standards. This interface also minimises the use of custom message types, which favours accessibility in some environments. Not all signals are available on this interface—for instance, camera and microphone data are published on the Platform Interface.
Downstream control signals on this interface can be processed at the hi-rate (50Hz). If they are delivered at less than 5Hz, inputs on this interface are not processed smoothly (outputs on this interface are always published at full rate). Publishing to this interface at 10Hz, say, is thus entirely satisfactory, though higher-rate control will also be processed correctly.
Upstream
sensors/body_vel
ROS stream specification | |
---|---|
stream description | body velocity odometry (from main wheels) |
topic name | sensors/body_vel |
message type | geometry_msgs/Twist |
content | Odometry velocity for forward (linear.x in m/s) and rotational (angular.z in Rad/s) motion of body (other elements of the object are zero). |
sensors/odom
This topic offers the same information as sensors/body_vel in a standard nav_msgs/Odometry
format.
sensors/kinematic_joints
ROS stream specification | |
---|---|
stream description | position/velocity of internal kinematic joints (tilt, lift, yaw, and pitch) |
topic name | sensors/kinematic_joints |
message type | sensor_msgs/JointState |
content | Sensed position (Rad) and velocity (Rad/s) for each of four kinematic joints: tilt, lift, yaw, and pitch (tilt is not implemented on current robots). |
Other Sensors
The remaining sensors are packaged as shown in the diagram—explore their output using rostopic echo
to learn exactly how they function (hint: cliff sensors read up to 15!).
Downstream
control/cmd_vel
ROS stream specification | |
---|---|
stream description | velocity drive signal for body velocity (through main wheels) |
topic name | control/cmd_vel |
message type | geometry_msgs/Twist |
content | Command velocity for forward (linear.x in m/s) and rotational (angular.z in Rad/s) motion of body (other elements of the object are ignored).To control individual wheel speeds, see example below. |
The following Python example shows how to control the speed of the individual wheels directly, through the control/cmd_vel
interface, if required.
control/kinematic_joints
ROS stream specification | |
---|---|
stream description | position/velocity drive signal for internal kinematic joints (tilt, lift, yaw, and pitch) |
topic name | control/kinematic_joints |
message type | sensor_msgs/JointState |
content | Command position (Rad) and velocity (Rad/s) for each of four kinematic joints: tilt, lift, yaw, and pitch (tilt is not implemented on current robots). |
MIRO_P2U_W_LEAN_SPEED_INF
(defined in miro_constants.h
or share/miro_constants/miro.py
) is a special value which means "infinite" (get there as quickly as possible); this is the right value to use if the trajectory over time is being managed through the position signal.control/cosmetic_joints
ROS stream specification | |
---|---|
stream description | position for cosmetic joints |
topic name | control/cosmetic_joints |
message type | std_msgs/Float32MultiArray |
content | Command position (normalized) for each of four cosmetic joints: eyelids, left ear, right ear, tail. Values are between 0 and 1 for each, except for tail which ranges from -1 (fully drooped) through 0 (neutral) to +1 (maximum wagging). |
control/lights
ROS stream specification | |
---|---|
stream description | low-level control signals for light (LED) arrays |
topic name | control/lights |
message type | std_msgs/UInt16MultiArray |
content | Array must contain 18 values, each the intensity of one lighting channel in 0-255. Array is organised as [red, green, blue], then as [front, middle, back], then as [left, right]. |