Overview

Section Message Description
actuators ActuatorGroupProto A message used to send actuator commands to hardware (or simulated hardware)
alice LogMessageProto Header for logging messages
LogPoseProto A message which contains a transformation from the pose tree. Used for logging the pose tree.
MessageChannelIndexProto An index containing all message channels in a log
MessageHeaderProto A message header which is sent together with the actual message. It allows the remote to forward the message to the correct receiver and it also provides timing information based on the transmitter clock.
UdpPackageHeaderProto A small header for every package we send over a UDP socket. It allows the remote to reassemble the message
audio AudioDataProto Message containing input to the audio playback module
audio_file_playback AudioFilePlaybackProto Notifies the audio file loader module the file to play
bodies RigidBody3GroupProto A list of rigid bodies in a certain coordinate frame
RigidBody3Proto A rigid body in 3D
camera ColorCameraProto An image published by a color (or greyscale) camera
DepthCameraProto Depth information for an image
DisparityCameraProto Disparity information for an image
DistortionProto Distortion parameters for a camera image
PinholeProto Pinhole camera model parameters
SegmentationCameraProto Pixel-wise class label and instance segmentations for an image
chat_message ChatMessageProto A chat message
detections Detections2Proto A message containing detections made by sensor(s) Each detection has a bounding box, label, and confidence
Detections3Proto A message containing detections made by sensor(s) Each detection has a 3D pose, label, and confidence
PredictionProto A prediction gives a class name with a confidence level from 0 to 1
differential_base DifferentialBaseStateProto A state message to receive important information from a differential base
dynamixel DynamixelMotorsProto Commands commands for a set of dynamixel motors running for example as a dasy chain.
fiducials FiducialListProto A list of detected ficucials
FiducialProto A fiducial is an object placed in the field of view of an imaging system for use as a point of reference or a measure
geometry PlaneProto A plane in three-dimensional space
RectangleProto A rectangle using 64-bit doubles
heatmap HeatmapProto Describes the heatmap of probabilities for different units
imu ImuProto Message published by an inertial measurement unit (IMU)
joystick JoystickStateProto Messages published from a gamepad controller.
lidar FlatscanProto A 2D range scan which is essentially a flat version of the 3D RangeScanProto
PointCloudProto A message about a cloud of 3D points.
RangeScanProto A message about laser range scans published for example from a LIDAR sensor The message does not have to capture a full 360 degree scan, as most sensors publish partial slices at high frequency instead of waiting to complete a full scan.
math Pose2dProto A pose for 2-dimensional space with rotation and translation using 64-bit doubles
Pose2fProto A pose for 2-dimensional space with rotation and translation using 32-bit floats
Pose3dProto A pose for 3-dimensional space with rotation and translation using 64-bit doubles
Pose3fProto A pose for 3-dimensional space with rotation and translation using 32-bit floats
QuaterniondProto A quaternion using 64-bit doubles for example to represent rotations
QuaternionfProto A quaternion using 32-bit floats for example to represent rotations
SO2dProto A rotation in 2-dimensional Euclidean space using 64-bit doubles
SO2fProto A rotation in 2-dimensional Euclidean space using 32-bit floats
SO3dProto A rotation in 3-dimensional Euclidean space using 64-bit doubles
SO3fProto A rotation in 3-dimensional Euclidean space using 32-bit floats
Vector2dProto A 2-dimensional vector using 64-bit doubles
Vector2fProto A 2-dimensional vector using 32-bit floats
Vector2iProto A 2-dimensional vector using 32-bit integers
Vector3dProto A 3-dimensional vector using 64-bit doubles
Vector3fProto A 3-dimensional vector using 32-bit floats
Vector3iProto A 3-dimensional vector using 32-bit integers
Vector4dProto A 4-dimensional vector using 64-bit doubles
Vector4fProto A 4-dimensional vector using 32-bit floats
Vector4iProto A 4-dimensional vector using 32-bit integers
Vector5dProto A 5-dimensional vector using 64-bit doubles
Vector5fProto A 5-dimensional vector using 32-bit floats
Vector5iProto A 5-dimensional vector using 32-bit integers
ml SegmentationPredictionProto Segmentation prediction proto stores the probability distribution over classes for each pixel in a three dimensional tensor. The probability will add up to one for each pixel.
mocap MarkerListProto Representation of raw marker info tracked by a motion capture system
navigation BinaryMapProto A binary occupancy grid map which indicates for every grid cell if the cell is free or occupied.
DifferentialState Describes how an entity is moving through space in a local diverging coordinate frame.
DifferentialTrajectoryPlanProto A trajectory plan for a differential base consisting of a sequence of states
DistanceMapProto A distance grid map which provides the distance to the nearest obstacle for every grid cell.
Goal2FeedbackProto A status update which is sent continously as a reply to receiving a goal message. This can be used to keep track if the robot has arrived at the destination.
Goal2Proto Describe a goal in a given referential frame
GoalWaypointProto A desired target waypoint
GroundPlaneProto A message describing the location of the ground.
OccupancyMapProto An occupancy grid map which provides mean and standard deviation for every grid cell. This represents the average number of times a cell was observed as occupied.
Odometry2Proto Describes how an entity is moving through space in a local diverging coordinate frame.
Plan2Proto Describes a plan in a given referential frame.
obstacles ObstaclesProto A message containing all obstacles around the robot
ping PingProto A generic message to ping another node with a private message.
posetree PoseTreeProto Pose tree/kinematic tree: hierarchicial kinematic representation
pwm_controller PwmChannelSetDutyCycleProto Set a duty cycle for a given PWM channel
PwmChannelSetPulseLengthProto Set a pulse length for a given PWM channel
robot_state RobotStateProto The robot state at that particular instance of time. The proto stores the current position and angle, as well as the difference between the previous values of the states (position and angle). Also contains the current linear and angular speed, obtained from odometry input
state StateProto A message used to transport states of dynamic systems. This is used closely together with the state gem to be found in //engine/gems/state. For example you can define the robot state using the compile-time types defined in that gem, and then serialize that state into a message. The receiver of that message can deserialize the state back into the compile-time robot state type.
tensor ImageProto An image produced for example by a camera
TensorListProto A list of tensors used for example as input or output for neural networks
TensorProto A n-dimensional tensor
uuid UuidProto A unique identifier following the UUID specifications
voice_command_detection VoiceCommandDetectionProto Message containing detected command id and list of timestamps of contributing keywords

Protobuffers

actuators

# A message used to send actuator commands to hardware (or simulated hardware)
struct ActuatorGroupProto {
  # The semantic meaning of the value
  # Represents angular/linear values depending on the joint type
  enum Semantics {
    position @0;
    speed @1;
    acceleration @2;
    force @3;
  }
  # A commanded property
  struct Value {
    semantics @0: Semantics;
    # the actual control or state value
    scalar @1: Float32;
  }
  # Just holds a list of commands per actuator
  struct CommandList {
    commands @0: List(Value);
  }
  # Desired commands per actuators
  actuators @0: List(CommandList);
  # (optional) names of actuators
  names @1: List(Text);
}

alice

# Header for logging messages
struct LogMessageProto {
  acqtime @0: Int64;
  pubtime @1: Int64;
  contentsUuid @2: UuidProto;
}
# A message which contains a transformation from the pose tree. Used for logging the pose tree.
struct LogPoseProto {
  pose @0: Pose3dProto;
  lhs @1: UuidProto;
  rhs @2: UuidProto;
}
# An index containing all message channels in a log
struct MessageChannelIndexProto {
  struct MessageChannel {
    # UUID of the app component
    componentUuid @0: UuidProto;
    # Tag of the message channel (as specified in ISAAC_PROTO_TX)
    tag @1: Text;
    # Series UUID under which messages are stored in the log
    seriesUuid @2: UuidProto;
  }
  channels @0: List(MessageChannel);
}
# A message header which is sent together with the actual message.
# It allows the remote to forward the message to the correct receiver and it also provides timing
# information based on the transmitter clock.
struct MessageHeaderProto {
  # Uniquely identifies a message across all systems
  uuid @0: UuidProto;
  # Uniquely identifies a proto type across all systems
  proto @1: Int64;
  # A channel identifier which is used to route messages
  channel @2: Text;
  # A (local) timestamp in nanoseconds which describes when data relevant for this message was
  # aquired by the hardware.
  acqtime @3: Int64;
  # A (local) timestamp in nanoseconds which describes when the message was published.
  pubtime @4: Int64;
  # Total length (in bytes) of message header and message payload
  messageLength @5: UInt32;
  # Lengths (in bytes) of proto segments
  segmentLengths @6: List(UInt32);
}
# A small header for every package we send over a UDP socket.
# It allows the remote to reassemble the message
struct UdpPackageHeaderProto {
  # Uniquely identifies a message across all systems
  uuid @0: UuidProto;
  # The total length of the message (header plus message payload) in bytes
  messageLength @1: UInt32;
  # The index of this package (assuming a fixed package size). The message header is always a
  # single package which comes first.
  packageIndex @2: UInt16;
}

audio

# Message containing input to the audio playback module
struct AudioDataProto {
  # Audio Sample Rate (eg. 44100, 48000, 96000, 192000)
  sampleRate @0: UInt32;
  # Number of channels in the Audio packet
  numChannels @1: UInt8;
}

audio_file_playback

# Notifies the audio file loader module the file to play
struct AudioFilePlaybackProto {
  # File index
  fileIndex @0: UInt8;
}

bodies

# A list of rigid bodies in a certain coordinate frame
struct RigidBody3GroupProto {
  # List of rigid bodies
  bodies @0: List(RigidBody3Proto);
  # Optional names for rigid bodies
  names @1: List(Text);
  # Name of coordinate system reference frame
  referenceFrame @2: Text;
}
# A rigid body in 3D
struct RigidBody3Proto {
  # The pose of the rigid body with respect to its reference coordinate frame
  refTBody @0: Pose3dProto;
  # The linear velocity in the reference coordinate frame
  linearVelocity @1: Vector3dProto;
  # The angular velocity as a Rodrigues vector in the reference coordinate frame. This means
  # the vector's direction is the axis of rotation and its length is the angular speed around
  # that axis.
  angularVelocity @2: Vector3dProto;
  # The linear acceleration
  linearAcceleration @3: Vector3dProto;
  # The angular acceleration
  angularAcceleration @4: Vector3dProto;
  # The relative scales in x, y, z axis in the body frame; (1.0, 1.0, 1.0) represents the original
  # scale.
  scales @5: Vector3dProto;
}

camera

# An image published by a color (or greyscale) camera
struct ColorCameraProto {
  # Actual image captured by the camera. The pixel type depends on the type of camera. Most commonly
  # it could be a single 8-bit integer for a greyscale camera, or a three 8-bit integers for a
  # color camera.
  image @0: ImageProto;
  # The choices available for color space
  enum ColorSpace {
    greyscale @0;
    rgb @1;
    bgr @2;
    yuv @3;
  }
  # Color space used by the image
  colorSpace @1: ColorSpace;
  # Intrinsic camera parameters
  pinhole @2: PinholeProto;
  distortion @3: DistortionProto;
}
# Depth information for an image
struct DepthCameraProto {
  # A depth value for every pixel in the image. The pixel type is a single 32-bit float.
  depthImage @0: ImageProto;
  # The minimum and maximum depth used
  minDepth @1: Float32;
  maxDepth @2: Float32;
  # Intrinsic camera parameters
  pinhole @3: PinholeProto;
}
# Disparity information for an image
struct DisparityCameraProto {
  # A disparity value for every pixel in the image. The pixel type is a single 32-bit float.
  disparityImage @0: ImageProto;
  # The minimum value that a pixel could be in the disparityImage.
  # This should be greater than zero so that a maximum depth can be computed.
  minimumDisparity @1: Float32;
  # The maximum value that a pixel could be in the disparityImage.
  maximumDisparity @2: Float32;
  # The distance between the two stereo cameras (in meters).
  cameraBaseline @3: Float32;
  # Intrinsic camera parameters
  pinhole @4: PinholeProto;
}
# Distortion parameters for a camera image
struct DistortionProto {
  # The choices available for the distortion model
  enum DistortionModel {
    # Brown distortion model with 3 radial and 2 tangential distortion
    # coefficients: (r0 r1 r2 t0 t1)
    brown @0;
    # Fisheye (wide-angle) distortion. 4 radial (r0, r1, r2, r3) distortion coefficients
    fisheye @1;
  }
  # Distortion model and coefficients
  model @0: DistortionModel;
  coefficients @1: Vector5fProto;
}
# Pinhole camera model parameters
struct PinholeProto {
  # Resolution of the camera
  rows @0: Int16;
  cols @1: Int16;
  # Focal length of the camera in pixel (0: row, 1: col)
  focal @2: Vector2dProto;
  # Optical center of the camera in pixel (0: row, 1: col)
  center @3: Vector2dProto;
}
# Pixel-wise class label and instance segmentations for an image
struct SegmentationCameraProto {
  # A image which stores a class label for every pixel. The pixel type is a single unsigned 8-bit
  # integer.
  labelImage @0: ImageProto;
  # A label used to enumerate all labels in the `labels` field below
  struct Label {
    # The integer value stored in the `labelImage`
    index @0: UInt8;
    # The name of the label
    name @1: Text;
  }
  # List of all labels used in labelImage
  labels @1: List(Label);
  # A image which stores an instance index for every pixel. Different objects with the same
  # label will get different instance indices. The pixel type is a single unsigned 16-bit integer.
  instanceImage @2: ImageProto;
  # Intrinsic camera parameters
  pinhole @3: PinholeProto;
}

chat_message

# A chat message
struct ChatMessageProto {
  # The user name of the sender
  user @0: Text;
  # A channel on which the message was posted
  channel @1: Text;
  # The text sent by the user
  text @2: Text;
}

detections

# A message containing detections made by sensor(s)
# Each detection has a bounding box, label, and confidence
struct Detections2Proto {
  # List of predictions made
  predictions @0: List(PredictionProto);
  # List of bounding boxes where we detected objects
  boundingBoxes @1: List(RectangleProto);
}
# A message containing detections made by sensor(s)
# Each detection has a 3D pose, label, and confidence
struct Detections3Proto {
  # List of predictions made
  predictions @0: List(PredictionProto);
  # List of poses of objects detected relative to the sensor frame
  poses @1: List(Pose3dProto);
}
# A prediction gives a class name with a confidence level from 0 to 1
struct PredictionProto {
  # Name or label for the detection
  label @0: Text;
  # A general value to indicate how confident we are about the detection.
  # This could for example be provided by a perception algorithm like a
  # neural network bounding box detector.
  confidence @1: Float64;
}

differential_base

# A state message to receive important information from a differential base
struct DifferentialBaseStateProto {
  # Current linear speed
  linearSpeed @0: Float64;
  # Current acceleration
  linearAcceleration @1: Float64;
  # Current angular speed
  angularSpeed @2: Float64;
  # Current angular acceleration
  angularAcceleration @3: Float64;
}

dynamixel

# Commands commands for a set of dynamixel motors running for example as a dasy chain.
struct DynamixelMotorsProto {
  # Motor protos
  struct MotorProto {
    # Motor ID
    id @0: Int64;
    # Current position
    position @1: Int16;
    # Tick in milliseconds since startup
    tick @2: Int64;
    # Is the servo moving
    moving @3: Bool;
  }
  # A single command per motor
  motors @0: List(MotorProto);
}

fiducials

# A list of detected ficucials
struct FiducialListProto {
  fiducialList @0: List(FiducialProto);
}
# A fiducial is an object placed in the field of view
# of an imaging system for use as a point of reference or a measure
struct FiducialProto {
  # A fiducial can be of type (April Tag, QRCode, Barcode or ARTag)
  enum Type {
    apriltag @0;
    qrcode @1;
    barcode @2;
    artag @3;
  }
  # Enum to identify the type of fiducial represented by the
  # proto instance
  type @0: Type;
  # Text field that identifies the ID of the fiducial
  # For April Tag, the id is of the format <TagFamily_ID>
  # Ex. If the decoded tag ID is 14 and belongs to TagFamily tag36h11,
  # The id is tag36h11_14
  id @1: Text;
  # 3D pose of the detected tag from the camera coordinates,
  # consisting of orientation (quaternion) and translation
  # Camera coordinate (X - right, Y - down, Z - outward)
  # Tag coordinate (X - right, Y - down, Z - opposite to tag face direction)
  # Tag coordinates are centered at tag's upper-left corner
  # ie. Pose has identity quaternion and zero translation, when tag is facing the camera and it's
  # upper-left corner is centered at the camera center
  cameraTTag @2: Pose3dProto;
  # Optional list of keypoints of the detected fiducial, in image space
  keypoints @3: List(Vector2dProto);
}

geometry

# A plane in three-dimensional space
struct PlaneProto {
  normal @0: Vector3dProto;
  offset @1: Float64;
}
# A rectangle using 64-bit doubles
struct RectangleProto {
  # (x, y) values of the lower left corner of the rectangle
  min @0: Vector2dProto;
  # (x, y) values of the upper right corner of the rectangle
  max @1: Vector2dProto;
}

heatmap

# Describes the heatmap of probabilities for different units
struct HeatmapProto {
  # Probability for each cell of the grid
  heatmap @0: ImageProto;
  # Name of the frame of the map (as registered in the PoseTree)
  frameName @1: Text;
  # Size of a pixel in meters
  gridCellSize @2: Float32;
}

imu

# Message published by an inertial measurement unit (IMU)
struct ImuProto {
  # The linear acceleration of the body frame along the primary axes
  linearAccelerationX @0: Float32;
  linearAccelerationY @1: Float32;
  linearAccelerationZ @2: Float32;
  # The angular velocity of the body frame around the primary axes
  angularVelocityX @3: Float32;
  angularVelocityY @4: Float32;
  angularVelocityZ @5: Float32;
  # Optional angles as integrated by a potential internal estimator
  angleYaw @6: Float32;
  anglePitch @7: Float32;
  angleRoll @8: Float32;
}

joystick

# Messages published from a gamepad controller.
struct JoystickStateProto {
  # State of gamepad axes
  axes @0: List(Vector2dProto);
  # State of gamepad buttons
  buttons @1: List(Bool);
}

lidar

# A 2D range scan which is essentially a flat version of the 3D RangeScanProto
struct FlatscanProto {
  # Angles (in radians) under which rays are shot
  angles @0: List(Float32);
  # Return distance of the ray
  ranges @1: List(Float32);
  # Beams with a range smaller than or equal to this distance are considered to have returned an
  # invalid measurement.
  invalidRangeThreshold @2: Float64;
  # Beams with a range larger than or equal to this distance are considered to not have hit an
  # obstacle within the maximum possible range of the sensor.
  outOfRangeThreshold @3: Float64;
}
# A message about a cloud of 3D points.
struct PointCloudProto {
  # The positions of the poinst
  positions @0: List(Vector3fProto);
  # The colors of the points. This is optional, but if present must have the same length as `points`.
  colors @1: List(Vector3fProto);
  # The intensity of points used for example by LIDAR sensors. This is optional, but if present must
  # have the same length as `points`.
  intensities @2: List(Float32);
}
# A message about laser range scans published for example from a LIDAR sensor
# The message does not have to capture a full 360 degree scan, as most sensors publish partial
# slices at high frequency instead of waiting to complete a full scan.
struct RangeScanProto {
  struct Ray {
    # Normalized distance to target (see rangeScale)
    range @0: UInt16;
    # Normalized ray return intensity (see intensityScale)
    intensity @1: UInt8;
  }
  # The range and intensity of the scanned rays. For each angle theta there is a ray
  # for every phi angle. So the total number of rays is length(theta) * length(size).
  rays @0: List(Ray);
  # table of theta (horizontal) angles
  theta @1: List(Float32);
  # table of phi (vertical) angles
  phi @2: List(Float32);
  # Scale factor which can be used to convert a range value from a 16-bit integer to meters. The
  # conversion formula is: range[meters] = range[normalized] / 0xFFFF * rangeScale
  rangeDenormalizer @3: Float32;
  # Scale factor which can be used to convert an intensity value from an 8-bit integer to meters.
  # The conversion formula is: intensity = intensity[normalized] / 0xFF * rangeScale
  intensityDenormalizer @4: Float32;
  # Delay in microseconds between firing
  deltaTime @5: UInt16;
  # Beams with a range smaller than or equal to this distance (in meters) are considered to have
  # returned an invalid measurement.
  invalidRangeThreshold @6: Float64;
  # Beams with a range larger than or equal to this distance (in meters) are considered to not have
  # hit an obstacle within the maximum possible range of the sensor.
  outOfRangeThreshold @7: Float64;
}

math

# A pose for 2-dimensional space with rotation and translation using 64-bit doubles
struct Pose2dProto {
  rotation @0: SO2dProto;
  translation @1: Vector2dProto;
}
# A pose for 2-dimensional space with rotation and translation using 32-bit floats
struct Pose2fProto {
  rotation @0: SO2fProto;
  translation @1: Vector2fProto;
}
# A pose for 3-dimensional space with rotation and translation using 64-bit doubles
struct Pose3dProto {
  rotation @0: SO3dProto;
  translation @1: Vector3dProto;
}
# A pose for 3-dimensional space with rotation and translation using 32-bit floats
struct Pose3fProto {
  rotation @0: SO3fProto;
  translation @1: Vector3fProto;
}
# A quaternion using 64-bit doubles for example to represent rotations
struct QuaterniondProto {
  w @0: Float64;
  x @1: Float64;
  y @2: Float64;
  z @3: Float64;
}
# A quaternion using 32-bit floats for example to represent rotations
struct QuaternionfProto {
  w @0: Float32;
  x @1: Float32;
  y @2: Float32;
  z @3: Float32;
}
# A rotation in 2-dimensional Euclidean space using 64-bit doubles
struct SO2dProto {
  # unit complex number (cos(a), sin(a)) for rotation angle a
  q @0: Vector2dProto;
}
# A rotation in 2-dimensional Euclidean space using 32-bit floats
struct SO2fProto {
  # unit complex number (cos(a), sin(a)) for rotation angle a
  q @0: Vector2fProto;
}
# A rotation in 3-dimensional Euclidean space using 64-bit doubles
struct SO3dProto {
  # a normalized quaternion
  q @0: QuaterniondProto;
}
# A rotation in 3-dimensional Euclidean space using 32-bit floats
struct SO3fProto {
  # a normalized quaternion
  q @0: QuaternionfProto;
}
# A 2-dimensional vector using 64-bit doubles
struct Vector2dProto {
  x @0: Float64;
  y @1: Float64;
}
# A 2-dimensional vector using 32-bit floats
struct Vector2fProto {
  x @0: Float32;
  y @1: Float32;
}
# A 2-dimensional vector using 32-bit integers
struct Vector2iProto {
  x @0: Int32;
  y @1: Int32;
}
# A 3-dimensional vector using 64-bit doubles
struct Vector3dProto {
  x @0: Float64;
  y @1: Float64;
  z @2: Float64;
}
# A 3-dimensional vector using 32-bit floats
struct Vector3fProto {
  x @0: Float32;
  y @1: Float32;
  z @2: Float32;
}
# A 3-dimensional vector using 32-bit integers
struct Vector3iProto {
  x @0: Int32;
  y @1: Int32;
  z @2: Int32;
}
# A 4-dimensional vector using 64-bit doubles
struct Vector4dProto {
  x @0: Float64;
  y @1: Float64;
  z @2: Float64;
  w @3: Float64;
}
# A 4-dimensional vector using 32-bit floats
struct Vector4fProto {
  x @0: Float32;
  y @1: Float32;
  z @2: Float32;
  w @3: Float32;
}
# A 4-dimensional vector using 32-bit integers
struct Vector4iProto {
  x @0: Int32;
  y @1: Int32;
  z @2: Int32;
  w @3: Int32;
}
# A 5-dimensional vector using 64-bit doubles
struct Vector5dProto {
  x @0: Float64;
  y @1: Float64;
  z @2: Float64;
  w @3: Float64;
  v @4: Float64;
}
# A 5-dimensional vector using 32-bit floats
struct Vector5fProto {
  x @0: Float32;
  y @1: Float32;
  z @2: Float32;
  w @3: Float32;
  v @4: Float32;
}
# A 5-dimensional vector using 32-bit integers
struct Vector5iProto {
  x @0: Int32;
  y @1: Int32;
  z @2: Int32;
  w @3: Int32;
  v @4: Int32;
}

ml

# Segmentation prediction proto stores the probability distribution over classes for each pixel in
# a three dimensional tensor. The probability will add up to one for each pixel.
struct SegmentationPredictionProto {
  # List of all class names. The number of elements must match the third dimension of the tensor.
  classNames @0: List(Text);
  # Tensor with dimensions (rows * cols * classes)
  prediction @1: TensorProto;
}

mocap

# Representation of raw marker info tracked by a motion capture system
struct MarkerListProto {
  # List of markers
  markers @0: List(Marker);
  # A motion captured marker
  struct Marker {
    # Marker name or label, if labeled in mocap system
    name @0: Text;
    # Name of node that this marker belongs to, if any
    # If unlabeled, parent is scene root
    parent @1: Text;
    # Translation of marker relative to the global origin
    worldTMarker @2: Vector3dProto;
    # True if marker is occluded in current frame, false otherwise
    occluded @3: Bool;
  }
}

obstacles

# A message containing all obstacles around the robot
struct ObstaclesProto {
  # A message containing the information about a spherical obstacle
  struct SphereObstacleProto {
    # The positions of the center in a given frame (see frame below)
    center @0: Vector3dProto;
    # The radius of the obstacle (include the minimal distance we aim to stay away from)
    radius @1: Float64;
    # The coordinate frame the center is located (must match a frame in the PoseTree)
    # deprecated: use robotFrame below instead.
    frame @2: Text;
    # Unique identifier the can be used to track the object
    uuid @3: UuidProto;
    # Time this obstacle was reported (used in the PoseTree)
    time @4: Float64;
  }
  # A distance map describes the distance to the closest obstacle for every pixel.
  struct DistanceMapProto {
    # The distance map as a 1d image. Each pixel contains the metric distance to the closest
    # obstacle
    image @0: ImageProto;
    # The pose of the gridmap relative to the robot
    robotTGridmap @1: Pose2dProto;
    # The size of a grid cell
    gridCellSize @2: Float64;
    # Time this obstacle was reported (used in the PoseTree)
    time @3: Float64;
  }
  # List of spherical obstacles (see SphereObstacleProto for details)
  obstacles @0: List(SphereObstacleProto);
  # List of distance maps (see DistanceMapProto for details)
  distanceMaps @1: List(DistanceMapProto);
  # The coordinate frame the center is located (must match a frame in the PoseTree)
  robotFrame @2: Text;
}

ping

# A generic message to ping another node with a private message.
struct PingProto {
  message @0: Text;
}

posetree

# Pose tree/kinematic tree: hierarchicial kinematic representation
struct PoseTreeProto {
  # Pose tree name
  name @0: Text;
  # List of all nodes in tree
  nodes @1: List(Node);
  # List of all edges between nodes in the tree, i.e. adjacency list
  edges @2: List(Edge);
  # Each node in the tree holds its pose relative to its immediate parent and its pose relative to the root
  struct Node {
    # Node name
    name @0: Text;
    # This node's parent index in the nodes list
    parentIndex @1: Int32;
    # Transformation of node relative to its parent
    parentTNode @2: Pose3dProto;
    # Transformation of node relative to global origin
    worldTNode @3: Pose3dProto;
  }
  # Each edge holds a parent name and child name
  # Every node knows its parent's index but this is for human readability
  struct Edge {
    # Parent name
    parentName @0: Text;
    # Child name
    childName @1: Text;
  }
}

pwm_controller

# Set a duty cycle for a given PWM channel
struct PwmChannelSetDutyCycleProto {
  channel @0: Int32;
  # PWM channel to set
  dutyCycle @1: Float32;
  # duty cycle, as a percentage (0.0 to 1.0)
  disable @2: Bool;
  # if set to true, duty cycle is ignored and power is set to 0
}
# Set a pulse length for a given PWM channel
struct PwmChannelSetPulseLengthProto {
  channel @0: Int32;
  # PWM channel to set
  pulseLength @1: Float32;
  # length of pulse, as a percentage (0.0 to 1.0)
}

robot_state

# The robot state at that particular instance of time. The proto stores the current position and
# angle, as well as the difference between the previous values of the states (position and angle).
# Also contains the current linear and angular speed, obtained from odometry input
struct RobotStateProto {
  # Current pose of robot in the world coordinate frame
  worldTRobot @0: Pose2dProto;
  # Current speed of body (x, y and angular)
  currentSpeed @1: Vector3dProto;
  # Distance travelled from last updated position
  displacementSinceLastUpdate @2: Vector3dProto;
}

state

# A message used to transport states of dynamic systems. This is used closely together with the
# state gem to be found in //engine/gems/state. For example you can define the robot state using the
# compile-time types defined in that gem, and then serialize that state into a message. The
# receiver of that message can deserialize the state back into the compile-time robot state type.
struct StateProto {
  # A densely packed representation of the state data as floating point numbers. The lowest rank
  # indicates state element dimension, the second rank is time for a potential timeseries, and
  # the third rank is for the batch index.
  pack @0: TensorProto;
  # The schema describing the format of the state vector
  schema @1: Text;
  # Alternative way to pass the data (for python)
  data @2: List(Float64);
}

tensor

# An image produced for example by a camera
struct ImageProto {
  # Type of channel elements
  elementType @0: ElementType;
  # Number of rows in the image
  rows @1: UInt16;
  # Number of columns in the image
  cols @2: UInt16;
  # Number of channels per pixel
  channels @3: UInt16;
  # Index of buffer which contains the image data
  dataBufferIndex @4: UInt16;
}
# A list of tensors used for example as input or output for neural networks
struct TensorListProto {
  tensors @0: List(TensorProto);
}
# A n-dimensional tensor
struct TensorProto {
  # Type of channel elements
  elementType @0: ElementType;
  # Dimensions of the tensor
  sizes @1: List(Int16);
  # Tensor element data as raw bytes
  data @2: Data;
}

uuid

# A unique identifier following the UUID specifications
struct UuidProto {
  # First 8 bytes out of 16
  lower @0: UInt64;
  # Second 8 bytes out of 16
  upper @1: UInt64;
}

voice_command_detection

# Message containing detected command id and list of timestamps of contributing keywords
struct VoiceCommandDetectionProto {
  # Detected command id
  commandId @0: UInt8;
  # List of timestamps of contributing keywords to the detected command
  timestamps @1: List(UInt64);
}