Message API Overview

Section Message Description
actor_group ActorGroupProto A message to request creation and destruction of actors in simulator
actuator_group ActuatorGroupProto A message used to send actuator commands to hardware (or simulated hardware)
alice LogMessageProto Header for logging messages
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.
PoseTreeEdgeProto Information about the pose releation between two coordinate frames.
UdpPackageHeaderProto A small header for every package we send over a UDP socket. It allows the remote to reassemble the message
audio_data AudioDataProto Message containing input to the audio playback module
audio_file_playback AudioFilePlaybackProto Notifies the audio file loader module the file to play
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
collision CollisionProto A collision event information
detections ConfusionMatrixProto A message to contain the evaluation results of an object detection algorithm. Contains the confusion matrices for the classes in a dataset accumulated over a certain number of images in the dataset.
Detections2Proto A message containing detections made by sensor(s), in the 2D image space Each detection has a bounding box and/or 2D pose, label, and confidence
Detections3Proto A message containing detections made by sensor(s), in the 3D space Each detection has a 3D pose, label, and confidence
PredictionProto A prediction gives a class name with a confidence level from 0 to 1
Skeleton2ListProto Defines a list of Skeleton2Proto messages.
Skeleton2Proto Defines a skeleton with 2D joint locations. Used for example to describe a human skeleton detected on an image.
differential_base 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
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
Odometry2Proto Describes how an entity is moving through space in a local diverging coordinate frame.
Plan2Proto Describes a plan in a given referential frame.
dynamixel_motors DynamixelMotorsProto Commands commands for a set of dynamixel motors running for example as a dasy chain.
fiducial_list 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
flatscan FlatscanProto A 2D range scan which is essentially a flat version of the 3D RangeScanProto
geometry GroundPlaneProto (deprecated) A message describing the location of the ground.
PlaneProto A plane in three-dimensional space
RectangleProto A rectangle using 64-bit doubles
graph GraphProto A general graph
heatmap HeatmapProto Describes the heatmap of probabilities for different units
imu ImuProto Message published by an inertial measurement unit (IMU)
joystick_state JoystickStateProto Messages published from a gamepad controller.
json JsonProto A proto transporting a JSON string encoded as a string
led_strip LedStripProto A message to describe a desired state of a LED display strip
map LatticeProto The information of a lattice coordinate system: it contains the name of frame registered in the PoseTree and the size of the cells.
marker_list MarkerListProto Representation of raw marker info tracked by a motion capture system
math Matrix3dProto A matrix with dimensions 3x3 using 64-bit floating points
Pose2MeanAndCovariance A type containing mean and covariance for a Pose2
Pose2Samples A list of samples of type Pose2
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
Vector3ubProto A 3-dimensional vector using unsigned 8-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
obstacles ObstaclesProto A message containing all obstacles around the robot
ping PingProto A generic message to ping another node with a private message.
point_cloud PointCloudProto A message containing information about a set of points , also called “point cloud”. Points can have various attributes. This message provides the position of the point in 3D space, a normal, a color and an intensity. Point attributes are each stored as NxM tensors. N is the number points which has to be identical for all attributes or 0. M is the dimension of the corresponding attribute.
pose_tree PoseTreeProto Pose tree/kinematic tree: hierarchicial kinematic representation
pwm_channel_set PwmChannelSetDutyCycleProto Set a duty cycle for a given PWM channel
PwmChannelSetPulseLengthProto Set a pulse length for a given PWM channel
range_scan 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.
rigid_body_3_group RigidBody3GroupProto A list of rigid bodies in a certain coordinate frame
RigidBody3Proto A rigid body in 3D
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
segmentation_prediction 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.
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.
superpixels SuperpixelLabelsProto Labels for superpixels. Assigns a label to every superpixel in a related SuperpixelsProto
SuperpixelsProto A superpixel oversegmentation for an image. This is useful for various image segmentation methods or perception algorithms in general. # Each pixel in the image is assigned to a superpixel. For each superpixel information like the pixel coordinate or the color are reported. Optionally also 3D data like point and normal are reported.
trajectory Vector3TrajectoryListProto A list of trajectories with three dimensions. For example, one might consider the multiple trajectories for given bodies.
Vector3TrajectoryProto A trajectory with three dimensions. The trajectory is composed of a time series of positions in reference to a given frame. For example, one might consider the trajectory of a moving target. Note: The timestamps may be omitted, in which case the trajectory is equivalent to a path.
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

actor_group

ActorGroupProto

Copy
Copied!
            

# A message to request creation and destruction of actors in simulator struct ActorGroupProto { # A request to spawn a new actor struct SpawnRequest { # The name given to the spawned actor. This name does not need to be unique. If multiple spawned # actors have the same name, the subsequent requests apply to all of them. name @0: Text; # The object template the spawned actor is instantiated from (e.g. a prefab name in Unity) prefab @1: Text; # The pose to set the spawned actor (in the simulator's reference frame) pose @2: Pose3dProto; } # List of spawn requests spawnRequests @0: List(SpawnRequest); # List of names of actors to destroy. destroyRequests @1: List(Text); }

actuator_group

ActuatorGroupProto

Copy
Copied!
            

# 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

LogMessageProto

Copy
Copied!
            

# Header for logging messages struct LogMessageProto { acqtime @0: Int64; pubtime @1: Int64; contentsUuid @2: UuidProto; }


MessageChannelIndexProto

Copy
Copied!
            

# 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); }


MessageHeaderProto

Copy
Copied!
            

# 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); }


PoseTreeEdgeProto

Copy
Copied!
            

# Information about the pose releation between two coordinate frames. struct PoseTreeEdgeProto { # Name of "left" frame, i.e. `lhs` for a pose `lhs_T_rhs` lhs @0: Text; # Name of "right" frame, i.e. `rhs` for a pose `lhs_T_rhs` rhs @1: Text; # The pose between the two frames using the orientation `lhs_T_rhs` pose @2: Pose3dProto; }


UdpPackageHeaderProto

Copy
Copied!
            

# 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_data

AudioDataProto

Copy
Copied!
            

# 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

AudioFilePlaybackProto

Copy
Copied!
            

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

camera

ColorCameraProto

Copy
Copied!
            

# 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; rgba @4; } # Color space used by the image colorSpace @1: ColorSpace; # Intrinsic camera parameters pinhole @2: PinholeProto; distortion @3: DistortionProto; }


DepthCameraProto

Copy
Copied!
            

# 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; }


DisparityCameraProto

Copy
Copied!
            

# 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; }


DistortionProto

Copy
Copied!
            

# 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; }


PinholeProto

Copy
Copied!
            

# 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; }


SegmentationCameraProto

Copy
Copied!
            

# 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

ChatMessageProto

Copy
Copied!
            

# 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; }

collision

CollisionProto

Copy
Copied!
            

# A collision event information struct CollisionProto { # The name of this collider thisName @0: Text; # The name of the other collider otherName @1: Text; # The pose of this collider with respect to its reference coordinate frame thisPose @2: Pose3dProto; # The pose of the other collider with respect to the same reference coordinate frame otherPose @3: Pose3dProto; # contact point of the collision in the reference coordinate frame contactPoint @4: Vector3dProto; # normal of the contact point in the reference coordinate frame contactNormal @5: Vector3dProto; # The relative linear velocity between the two colliding objects in the reference coordinate frame velocity @6: Vector3dProto; }

detections

ConfusionMatrixProto

Copy
Copied!
            

# A message to contain the evaluation results of an object detection algorithm. Contains the # confusion matrices for the classes in a dataset accumulated over a certain number of images in # the dataset. struct ConfusionMatrixProto { # Number of samples these metrics were accumulated over. If 1, then the confusion matrices hold # the results for a single sample. If greater than 1, then the counts that are contained in the # confusion matrices are summed over accumulated samples. numSamples @0: Int64; # List of threshold values used to compute the metrics for each class. Each threshold # corresponds to one confusion matrix in the confusionMatrices Tensor. # The metric on which the threshold is applied is dependent on the task. In case of object # detection, the threshold is typically applied for the IoU (Intersection over Union) score # between two bounding boxes. thresholds @1: List(Float64); # Tensor with dimensions (actual class * predicted class * IoU), where a slice of the tensor # across a single IoU is a confusion matrix. (See https://en.wikipedia.org/wiki/Confusion_matrix) # Each confusion matrix is calculated using the corresponding IoU threshold, which determines the # tolerance to bounding box error. A lower IoU corresponds to greater tolerance to bbox error. confusionMatrices @2: TensorProto; }


Detections2Proto

Copy
Copied!
            

# A message containing detections made by sensor(s), in the 2D image space # Each detection has a bounding box and/or 2D pose, label, and confidence struct Detections2Proto { # List of predictions made predictions @0: List(PredictionProto); # List of 2D bounding boxes where we detected objects boundingBoxes @1: List(RectangleProto); # List of 2D poses of objects detected. Optional field. poses @2: List(Pose2dProto); }


Detections3Proto

Copy
Copied!
            

# A message containing detections made by sensor(s), in the 3D space # Each detection has a 3D pose, label, and confidence struct Detections3Proto { # List of predictions made predictions @0: List(PredictionProto); # List of 3D poses of objects detected relative to the sensor frame poses @1: List(Pose3dProto); }


PredictionProto

Copy
Copied!
            

# 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; }


Skeleton2ListProto

Copy
Copied!
            

# Defines a list of Skeleton2Proto messages. struct Skeleton2ListProto { # List of skeleton models skeletons @0: List(Skeleton2Proto); }


Skeleton2Proto

Copy
Copied!
            

# Defines a skeleton with 2D joint locations. Used for example to describe # a human skeleton detected on an image. struct Skeleton2Proto { # A graph defining the topology of the skeleton. graph @0: GraphProto; # Information about a joint in the skeleton struct Joint2Proto { # Location of the joint, for example image pixel coordinates. position @0: Vector2dProto; # A label and confidence, describing the prediction of the joint label @1: PredictionProto; } # Detailed information for every joint in the skeleton. The number of # joints must be identical to the number of nodes in the graph. joints @1: List(Joint2Proto); # A label and confidence, describing the prediction of the skeleton label @2: PredictionProto; }

differential_base

DifferentialState

Copy
Copied!
            

# Describes how an entity is moving through space in a local diverging coordinate frame. struct DifferentialState { positionX @0: Float64; positionY @1: Float64; heading @2: Float64; speedX @3: Float64; speedY @4: Float64; angularSpeed @5: Float64; timestamp @6: Float64; }


DifferentialTrajectoryPlanProto

Copy
Copied!
            

# A trajectory plan for a differential base consisting of a sequence of states struct DifferentialTrajectoryPlanProto { # List of states the robot will need to be. states @0: List(DifferentialState); # name of the frame the plan is planFrame @1: Text; }


Goal2FeedbackProto

Copy
Copied!
            

# 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. struct Goal2FeedbackProto { # Remaining relative pose to the goal, or identity in case hasGoal is false. robotTGoal @0: Pose2dProto; # Whether the robot currently has a goal hasGoal @1: Bool; # Whether the robot considers himself to be arrived at the target hasArrived @2: Bool; # Whether the robot considers himself to not move anymore isStationary @3: Bool; }


Goal2Proto

Copy
Copied!
            

# Describe a goal in a given referential frame struct Goal2Proto { # The goal expressed in Pose2 goal @0: Pose2dProto; # the tolerance radius of the goal. tolerance @1: Float32; # name of the frame the goal is. goalFrame @2: Text; # Whether or not we should stop the robot. If set to true all the other parameters will be ingored stopRobot @3: Bool; }


GoalWaypointProto

Copy
Copied!
            

# A desired target waypoint struct GoalWaypointProto { # the name of the waypoint waypoint @0: Text; }


Odometry2Proto

Copy
Copied!
            

# Describes how an entity is moving through space in a local diverging coordinate frame. struct Odometry2Proto { # The pose of the "robot" relative to the reference odometric frame odomTRobot @0: Pose2dProto; speed @1: Vector2dProto; angularSpeed @2: Float64; acceleration @3: Vector2dProto; # Contains the name of the odometry frame and the robot frame. odometryFrame @4: Text; robotFrame @5: Text; }


Plan2Proto

Copy
Copied!
            

# Describes a plan in a given referential frame. struct Plan2Proto { # List of poses the robot need to go through poses @0: List(Pose2dProto); # name of the frame the plan is. planFrame @1: Text; }

dynamixel_motors

DynamixelMotorsProto

Copy
Copied!
            

# 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); }

element_type

fiducial_list

FiducialListProto

Copy
Copied!
            

# A list of detected ficucials struct FiducialListProto { fiducialList @0: List(FiducialProto); }


FiducialProto

Copy
Copied!
            

# 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); }

flatscan

FlatscanProto

Copy
Copied!
            

# 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; # Return the visibility of a given ray (the longest valid distance of a beams in this direction) # This field is optional, however if it is set, it must have the same size as ranges and angles. visibilities @4: List(Float32); }

geometry

GroundPlaneProto

Copy
Copied!
            

# (deprecated) A message describing the location of the ground. struct GroundPlaneProto { # The ground plane. plane @0: PlaneProto; }


PlaneProto

Copy
Copied!
            

# A plane in three-dimensional space struct PlaneProto { normal @0: Vector3dProto; offset @1: Float64; }


RectangleProto

Copy
Copied!
            

# 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; }

graph

GraphProto

Copy
Copied!
            

# A general graph struct GraphProto { # The number of nodes in the graph. Indices in the list of edges will # always be smaller than this number. nodeCount @0: Int32; # An edge in the graph connects two nodes. struct EdgeProto { source @0: Int32; target @1: Int32; } # The edges of the graph. edges @1: List(EdgeProto); }

heatmap

HeatmapProto

Copy
Copied!
            

# 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; }

image

imu

ImuProto

Copy
Copied!
            

# 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_state

JoystickStateProto

Copy
Copied!
            

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

json

JsonProto

Copy
Copied!
            

# A proto transporting a JSON string encoded as a string struct JsonProto { # The serialized JSON object serialized @0: Text; }

led_strip

LedStripProto

Copy
Copied!
            

# A message to describe a desired state of a LED display strip struct LedStripProto { # Light strip status. If false, the LED strip is powered off. # If true, the LED strip displays the pattern and color # defined by the following parameters of this message. enabled @0: Bool; # Color to display, in RGB format color @1: Vector3ubProto; # Number of LEDs to skip when displaying this color. The remaining # LEDs will be unchanged. skip @2: Int32; # If a skip value is defined, the offset is the index of LED to start # the skip pattern. i.e. To set every other LED # starting from the third LED use skip = 2, offset = 3 offset @3: Int32; }

map

LatticeProto

Copy
Copied!
            

# The information of a lattice coordinate system: it contains the name of frame registered in the # PoseTree and the size of the cells. struct LatticeProto { # The name of frame as registered in the PoseTree frame @0: Text; # The size of a grid cell in meters cellSize @1: Float64; # The dimensions of the lattice grid. dimensions @2: Vector2iProto; }

marker_list

MarkerListProto

Copy
Copied!
            

# 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; } }

math

Matrix3dProto

Copy
Copied!
            

# A matrix with dimensions 3x3 using 64-bit floating points struct Matrix3dProto { row1 @0: Vector3dProto; row2 @1: Vector3dProto; row3 @2: Vector3dProto; }


Pose2MeanAndCovariance

Copy
Copied!
            

# A type containing mean and covariance for a Pose2 struct Pose2MeanAndCovariance { # The mean of the distribution mean @0: Pose2dProto; # The covariance of the distribution in the reference frame of the mean. covariance @1: Matrix3dProto; }


Pose2Samples

Copy
Copied!
            

# A list of samples of type Pose2 struct Pose2Samples { # The state for every sample states @0: List(Pose2dProto); # A weight for every sample. Optional and default is equal weighting. weights @1: List(Float64); }


Pose2dProto

Copy
Copied!
            

# A pose for 2-dimensional space with rotation and translation using 64-bit doubles struct Pose2dProto { rotation @0: SO2dProto; translation @1: Vector2dProto; }


Pose2fProto

Copy
Copied!
            

# A pose for 2-dimensional space with rotation and translation using 32-bit floats struct Pose2fProto { rotation @0: SO2fProto; translation @1: Vector2fProto; }


Pose3dProto

Copy
Copied!
            

# A pose for 3-dimensional space with rotation and translation using 64-bit doubles struct Pose3dProto { rotation @0: SO3dProto; translation @1: Vector3dProto; }


Pose3fProto

Copy
Copied!
            

# A pose for 3-dimensional space with rotation and translation using 32-bit floats struct Pose3fProto { rotation @0: SO3fProto; translation @1: Vector3fProto; }


QuaterniondProto

Copy
Copied!
            

# 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; }


QuaternionfProto

Copy
Copied!
            

# 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; }


SO2dProto

Copy
Copied!
            

# 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; }


SO2fProto

Copy
Copied!
            

# 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; }


SO3dProto

Copy
Copied!
            

# A rotation in 3-dimensional Euclidean space using 64-bit doubles struct SO3dProto { # a normalized quaternion q @0: QuaterniondProto; }


SO3fProto

Copy
Copied!
            

# A rotation in 3-dimensional Euclidean space using 32-bit floats struct SO3fProto { # a normalized quaternion q @0: QuaternionfProto; }


Vector2dProto

Copy
Copied!
            

# A 2-dimensional vector using 64-bit doubles struct Vector2dProto { x @0: Float64; y @1: Float64; }


Vector2fProto

Copy
Copied!
            

# A 2-dimensional vector using 32-bit floats struct Vector2fProto { x @0: Float32; y @1: Float32; }


Vector2iProto

Copy
Copied!
            

# A 2-dimensional vector using 32-bit integers struct Vector2iProto { x @0: Int32; y @1: Int32; }


Vector3dProto

Copy
Copied!
            

# A 3-dimensional vector using 64-bit doubles struct Vector3dProto { x @0: Float64; y @1: Float64; z @2: Float64; }


Vector3fProto

Copy
Copied!
            

# A 3-dimensional vector using 32-bit floats struct Vector3fProto { x @0: Float32; y @1: Float32; z @2: Float32; }


Vector3iProto

Copy
Copied!
            

# A 3-dimensional vector using 32-bit integers struct Vector3iProto { x @0: Int32; y @1: Int32; z @2: Int32; }


Vector3ubProto

Copy
Copied!
            

# A 3-dimensional vector using unsigned 8-bit integers struct Vector3ubProto { x @0: UInt8; y @1: UInt8; z @2: UInt8; }


Vector4dProto

Copy
Copied!
            

# A 4-dimensional vector using 64-bit doubles struct Vector4dProto { x @0: Float64; y @1: Float64; z @2: Float64; w @3: Float64; }


Vector4fProto

Copy
Copied!
            

# A 4-dimensional vector using 32-bit floats struct Vector4fProto { x @0: Float32; y @1: Float32; z @2: Float32; w @3: Float32; }


Vector4iProto

Copy
Copied!
            

# A 4-dimensional vector using 32-bit integers struct Vector4iProto { x @0: Int32; y @1: Int32; z @2: Int32; w @3: Int32; }


Vector5dProto

Copy
Copied!
            

# 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; }


Vector5fProto

Copy
Copied!
            

# 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; }


Vector5iProto

Copy
Copied!
            

# 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; }

obstacles

ObstaclesProto

Copy
Copied!
            

# 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

PingProto

Copy
Copied!
            

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

point_cloud

PointCloudProto

Copy
Copied!
            

# A message containing information about a set of points , also called "point cloud". Points can # have various attributes. This message provides the position of the point in 3D space, a normal, # a color and an intensity. Point attributes are each stored as NxM tensors. N is the number # points which has to be identical for all attributes or 0. M is the dimension of the corresponding # attribute. struct PointCloudProto { # The position of points. Most commonly XYZ stored as three 32-bit floats. positions @0: TensorProto; # A normal of the point. Most commonly a unit vector stored as three 32-bit floats. normals @1: TensorProto; # A color value for each point. Most commonly an RGB value stored as three 32-bit unit floats. colors @2: TensorProto; # The intensity for each point used for example by LiDAR sensors. Most commonly a single 32-bit # float. intensities @3: TensorProto; }

pose_tree

PoseTreeProto

Copy
Copied!
            

# 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_channel_set

PwmChannelSetDutyCycleProto

Copy
Copied!
            

# 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 }


PwmChannelSetPulseLengthProto

Copy
Copied!
            

# 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) }

range_scan

RangeScanProto

Copy
Copied!
            

# 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 { # Normalized distance to target (see rangeScale) of the scanned rays. Data type is 16-bit integer. # For each angle theta there is a ray for every phi angle. So the total number of rays is # length(theta) * length(phi). First rank is theta and second rank is phi. ranges @0: TensorProto; # Normalized ray return intensity (see intensityScale) of the scanned rays. Data type is 8-bit # integer. For each angle theta there is a ray for every phi angle. So the total number of rays is # length(theta) * length(phi). First rank is theta and second rank is phi. # This entry is optional. Default is full intensity for all rays. intensities @1: TensorProto; # table of theta (horizontal) angles theta @2: List(Float32); # table of phi (vertical) angles phi @3: 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 @4: 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 * intensityScale intensityDenormalizer @5: Float32; # Delay in microseconds between firing deltaTime @6: UInt16; # Beams with a range smaller than or equal to this distance (in meters) are considered to have # returned an invalid measurement. invalidRangeThreshold @7: 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 @8: Float64; }

rigid_body_3_group

RigidBody3GroupProto

Copy
Copied!
            

# 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; }


RigidBody3Proto

Copy
Copied!
            

# 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; }

robot_state

RobotStateProto

Copy
Copied!
            

# 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; }

segmentation_prediction

SegmentationPredictionProto

Copy
Copied!
            

# 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; }

state

StateProto

Copy
Copied!
            

# 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); }

superpixels

SuperpixelLabelsProto

Copy
Copied!
            

# Labels for superpixels. Assigns a label to every superpixel in a related SuperpixelsProto struct SuperpixelLabelsProto { labels @0: List(Int32); }


SuperpixelsProto

Copy
Copied!
            

# A superpixel oversegmentation for an image. This is useful for various image segmentation methods # or perception algorithms in general. # # Each pixel in the image is assigned to a superpixel. For each superpixel information like the # pixel coordinate or the color are reported. Optionally also 3D data like point and normal are # reported. struct SuperpixelsProto { # 2D superpixel data based on the color image struct Superpixel { # The average pixel coordinate of the superpixel stored as (row, col) pixel @0: Vector2fProto; # The average color of the superpixel stored as RGB in the range [0,1] color @1: Vector3fProto; # The number of pixels in this superpixel. There might be superpixels with count = 0 which # indicates that no pixels were assigned to them. This would also indicate that other superpixel # and surflet data is invalid. count @2: UInt32; } # Additional 3D surflet data for each superpixel defining the 3D shape of the superpixel struct Surflet { # 3D point coordinates of the surflet point @0: Vector3fProto; # 3D normal of the surflet normal @1: Vector3fProto; } # An image which assignes a superpixel image to every pixel using the superpixel index. This index # is identical to the position of the superpixel in the superpixels or surflet lists. Indices are # stored as an unsinged 16-bit integer. Pixels which are not assigned to any superpixel are marked # with the index 0xffff. indices @0: ImageProto; # 2D superpixel data for every pixel cluster superpixels @1: List(Superpixel); # 3D surflet data for every pixel cluster (optional) surflets @2: List(Surflet); }

tensor

trajectory

Vector3TrajectoryListProto

Copy
Copied!
            

# A list of trajectories with three dimensions. # For example, one might consider the multiple trajectories for given bodies. struct Vector3TrajectoryListProto { trajectories @0: List(Vector3TrajectoryProto); }


Vector3TrajectoryProto

Copy
Copied!
            

# A trajectory with three dimensions. # The trajectory is composed of a time series of positions in reference to a given frame. # For example, one might consider the trajectory of a moving target. # Note: The timestamps may be omitted, in which case the trajectory is equivalent to a path. struct Vector3TrajectoryProto { # A list of states as positions or samples. states @0: List(Vector3dProto); # An optional list of timestamps in seconds corresponding to the list of states or positions. timestamps @1: List(Float64); # The reference frame for this trajectory. frame @2: Text; }

uuid

UuidProto

Copy
Copied!
            

# 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

VoiceCommandDetectionProto

Copy
Copied!
            

# 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); }

© Copyright 2019, NVIDIA Corporation. Last updated on Feb 1, 2023.