BOW Data Message

Protocol Documentation

Table of Contents

Top

bow_data_audio.proto

AudioSample

AudioSample contains a single packet of audio data from a single source

FieldTypeLabelDescription
SourcestringSource indicates the origin of the audio data, such as a specific microphone.
DatabytesData contains the raw or compressed audio data.
Channelsuint32Channels specifies the number of audio channels.
SampleRateuint64SampleRate indicates the number of samples per second.
NumSamplesuint64NumSamples provides the total number of audio samples in the Data field.
CompressionAudioSample.CompressionFormatEnumCompression specifies the audio compression format used.
TransformTransformTransform provides the spatial location of the audio source, if applicable.
DesignationStereoDesignationEnumDesignation specifies whether the audio is intended for a specific channel in a stereo or multi-channel setup.

AudioSamples

AudioSamples contains multiple instances of audio data.

FieldTypeLabelDescription
SamplesAudioSamplerepeatedSamples is an array of AudioSample messages, each containing a sample of audio data from different sources

AudioSample.CompressionFormatEnum

CompressionFormatEnum lists available audio compression formats.

NameNumberDescription
RAW0Default: No compression
SPEEX1Compressed in Speex formats

Top

bow_data_common.proto

Environment

Environment provides temperature, pressure and humidity readings.

FieldTypeLabelDescription
TempfloatOptional: Temp provides the temperature measurement in Degrees Celcius
PressurefloatOptional: Pressure provides the pressure measurement in Pascals
HumidityfloatOptional: Humidity provides the humidity measurement between 0 and 1

Float32Array

Float32Array is a container for an array of floating-point numbers.

FieldTypeLabelDescription
DatafloatrepeatedData is an array of 32-bit floating-point numbers.

Int64Array

Int64Array is a container for an array of 64-bit integers.

FieldTypeLabelDescription
Dataint64repeatedData is an array of 64-bit integers.

Quaternion

Quaternion contains the components of a normalised quaternion that can be used to describe a rotation.

FieldTypeLabelDescription
QuatXfloatX component of the normalised quaternion
QuatYfloatY component of the normalised quaternion
QuatZfloatZ component of the normalised quaternion
QuatWfloatW component of the normalised quaternion

Transform

Transform captures a spatial point and orientation in Cartesian coordinates.

FieldTypeLabelDescription
PositionVector3Position utilises a Vector3 to define distances in metres from a designated reference point. X is positive to the right, Y is positive upwards, Z is positive forwards.
EulerAnglesVector3EulerAngles use a Vector3 to define rotation through specific angles, in units designated by AngleUnits.
LinkNamestringOptional: LocationTag identifies the origin point to which the transform is relative.
Partstring

Vector3

Vector3 contains three components expected for a vector in 3D cartesian space

FieldTypeLabelDescription
XfloatX component of the vector
YfloatY component of the vector
ZfloatZ component of the vector

ControllerEnum

ControlModeEnum specifies the controller currently applied to a specific kinematic chain

NameNumberDescription
POSITION_CONTROLLER0Default: POSITION_CONTROL uses inverse kinematics to control the position and orientation of the end effector at the end of the kinematic chain.
VELOCITY_CONTROLLER1VELOCITY_CONTROL is not currently available. (Upcoming functionality)
TORQUE_CONTROLLER2TORQUE_CONTROL is not currently available. (Upcoming functionality)

ObjectiveStatusEnum

NameNumberDescription
NO_OBJECTIVE0Default: No objective to provide a status for
PLANNING1Motion plan is being created
IN_PROGRESS2Objective is currently being executed
COLLISION_ERROR3Objective execution stopped due to collision
ERROR4Objective execution stopped due to error
WARNING5Warning raised
FINISHED6Objective finished successfully

RelativeToEnum

RelativeToEnum marks specific points on the robot for spatial reference.

NameNumberDescription
BASE0Default: Base indicates the robot's contact point with the floor.
HEAD1Head marks the robot's primary vision point, often where the main camera is located.
END_EFFECTOR2End_Effector identifies the terminal point of an articulated assembly.
END_EFFECTOR_LEFT3Identical to End_Effector but specifies the main articulated assembly on the left side of the robot.
END_EFFECTOR_RIGHT4Identical to End_Effector but specifies the main articulated assembly on the right side of the robot.
TORSO5Torso marks the robot's centre of mass.

StereoDesignationEnum

StereoDesignationEnum identifies the camera's role as part of a stereo pair or a microphone's role as part of a binaural pair. https://en.wikipedia.org/wiki/Stereo_camera (opens in a new tab)

NameNumberDescription
NONE0Default: Camera functions independently, not as part of a stereo pair.
LEFT1Camera operates as the left component in a stereo pair.
RIGHT2Camera operates as the right component in a stereo pair.

Top

bow_data_exteroception.proto

Compass

Compass provides the magnetic field along up to 3 axis

FieldTypeLabelDescription
MagVector3Mag represents the measured components of the magnetic field along each axis
TransformTransformTransform provides the spatial positioning of the compass

ExteroceptionSample

Exteroception contains sensor reading related to awareness of the surrounding environment

FieldTypeLabelDescription
LidarLidarrepeatedOptional: Lidar provides an array of range values representing the distances to objects at varying angles from a point
RangeRangerepeatedOptional: Range provides a distance or binary present/not present signal representing the output of a range sensor
ImuIMUrepeatedOptional: Imu provides the 3D acceleration, orientation, and gravitational forces experienced at different positions on a robot's body
GpsGPSOptional: Gps provides the global position of the robot, if available
CompassCompassOptional: Compass provides the magnetic field along up to 3 axis
EnvEnvironmentOptional: Environment provides temperature, pressure and humidity readings.
LightLightrepeatedOptional: Light provides a measurement of light/brightness at the location of the sensor

GPS

GPS captures geographic positioning data.

FieldTypeLabelDescription
LatitudefloatLatitude in decimal degrees
LongitudefloatLongitude in decimal degrees
ElevationfloatElevation in meters above sea level
TimestringTimestamp of the GPS sample

IMU

IMU (Inertial Measurement Unit) captures the sensor data needed to determine an object's orientation, velocity, and gravitational forces.

FieldTypeLabelDescription
GyroVector3Gyro represents angular velocity measured in radians per second along X, Y, and Z axes.
AccVector3Acc signifies linear acceleration in meters per second squared along X, Y, and Z axes.
OrientationVector3Optional: Returns the angular position of the IMU.
TransformTransformTransform provides a reference frame for the IMU data.

Lidar

Lidar provides an array of range values representing the distances to objects at varying angles from a central point

FieldTypeLabelDescription
DatafloatrepeatedData provides the distance to an obstacle within an angular segment of size defined by spatial resolution.
StartfloatOptional: Start provides the start angle of the scan, if not populated assumed to be 0 degrees
EndfloatEnd provides the end angle of the scan, if not populated assumed to be 360 degrees
AngularResolutionfloatAngularResolution specifies the granularity of the lidar data, the angle between each sample.
TemporalResolutionfloatTemporalResolution specifies the time between each sample.
TransformTransformTransform represents the spatial positioning of the lidar sensor at the time the data was captured.
NewDataFlagboolFlag which allows pre-setting of parameters awaiting new data

Light

Light provides a measurement of light/brightness at the location of the sensor

FieldTypeLabelDescription
DatafloatData provides the measurement of illuminance in Lux
MinfloatMin provides the minimum value for which readings from the sensor are valid
MaxfloatMax provides the maximum value for which readings from the sensor are valid
UnitLight.LightUnitEnumUnit provides the unit of the light measurement
TransformTransformTransform provides the spatial positioning of the sensor

Range

Range provides a distance or (present/not present) signal representing the output of a range sensor

FieldTypeLabelDescription
DatafloatData provides the distance to the nearest object in the field of view of the sensor
MinfloatMin provides the minimum range at which readings from the sensor are valid
MaxfloatMax provides the maximum range at which readings from the sensor are valid
FOVfloatFOV provides the field of view of the range sensor as an angle
SensorTypeRange.SensorTypeEnumSensorType provides the type of sensor which determines the expected output
OperationTypeRange.OperationTypeEnumOperationType provides the mechanism which the sensor uses for its operation, i.e. light, sound, mechanical.
TransformTransformTransform represents the spatial positioning of the range sensor at the time the data was captured.

Light.LightUnitEnum

NameNumberDescription
Lux0
Undefined1

Range.OperationTypeEnum

An enum defining physical mechanism used by the sensor

NameNumberDescription
Ultrasound0Sensor uses ultrasound for ranging, i.e. sonar
Infrared1Sensor uses infrared light for ranging, i.e. ToF
Mechanical2Sensor is a mechanical switch, i.e. cliff sensor

Range.SensorTypeEnum

An enum defining the type of range sensor

NameNumberDescription
Distance0Default: Sensor will return a range value
Proximity1Sensor will return a confidence value of object exists/doesn't exist

Top

bow_data_interoception.proto

Battery

FieldTypeLabelDescription
VoltagefloatVoltage provides the voltage reading across the battery
CurrentfloatCurrent provides the current draw in Amps
ChargefloatCharge provides charge in the battery in Amp Hours
PercentagefloatProvides the percentage charge of the battery remaining
PresentboolTrue if the battery is connected, otherwise False
SupplyStatusBattery.SupplyStatusEnumAn enum providing the status of the robots power supply/battery charger

InteroceptionSample

Interoception contains sensor readings related to the internal state of the robot

FieldTypeLabelDescription
EnvEnvironmentOptional: Env provides temperature, pressure and humidity readings from the inside of the robot
batteryBatteryBattery provides the current state of the battery
ErrorstringrepeatedA list of any provided error messages or codes

Battery.SupplyStatusEnum

NameNumberDescription
Unknown0
Charging1
Discharging2
Not_Charging3
Complete4

Top

bow_data_motor.proto

BodyPart

EndEffector defines an update to be sent to an articulated assembly, such as an arm or a leg

FieldTypeLabelDescription
NamestringOptional: Name of the end effector that this update is for. When not specified, position on array of EndEffectors is used to specify which command goes to which end effector
TypeBodyPart.BodyPartTypeEnum
RootLinkstring
EffectorsEffectorrepeated

CustomOptimiser

FieldTypeLabelDescription
OptimiserMethodCustomOptimiser.OptimiserMethodEnum
Iterationsint32
UseEvolutionbool

Effector

FieldTypeLabelDescription
EffectorLinkNamestring
EndTransformTransform
RootTransformTransform
Reachfloat
JointArrayJointrepeatedJointArray contain the angular positions of each joint in the articulated assembly, ordered according to the robot's specification. This is to enable manual control of the robot's joints if needed but should be avoided under normal circumstances because code will not be robot agnostic in behaviour. WARNING: NOT ROBOT AGNOSTIC
AvailableActionsActionEnumrepeated
WorkspaceOctreeNode
ObjectivesObjectiveFeedbackrepeated
IsControllablebool

GazeTarget

FieldTypeLabelDescription
GazeVectorVector3
VectorTypeGazeTarget.TargetTypeEnum

Gripper

Gripper outlines the configuration of a hand-like gripper in terms of each finger's position.

FieldTypeLabelDescription
GripperControlModeGripperModeEnum
HandMapPercentageHandMapPercentage
HandMapTransformHandMapTransform
JointArrayJointrepeated

GripperStatus

FieldTypeLabelDescription
GripperJointArrayJointrepeated
GripperOccupiedbool

HandMapPercentage

FieldTypeLabelDescription
ThumbfloatThumb specifies the % closed for the thumb [0-1] or distance of thumb-tip to palm.
IndexfloatIndex specifies the % closed for the index finger [0-1] or distance of index fingertip to palm.
MiddlefloatMiddle specifies the % closed for the middle finger [0-1] or distance of middle fingertip to palm.
RingfloatRing specifies the % closed for the ring finger [0-1] or distance of ring fingertip to palm.
PinkyfloatPinky specifies the % closed for the pinky finger [0-1] or distance of pinky fingertip to palm.
FingerAdductionfloatFingerAddiction specifies the spread of the fingers as a % [0-1]. Not used in DISTANCE_IK mode.
ThumbOppositionfloatThumbOpposition specifies the opposition of the thumb as a % [0-1]. Not used in DISTANCE_IK mode.

HandMapTransform

FieldTypeLabelDescription
CustomRefTransform
ThumbTransform
IndexTransform
MiddleTransform
RingTransform
PinkyTransform
TargetObjectObject

IKOptimiser

FieldTypeLabelDescription
PresetIKOptimiser.OptimiserPreset
CustomSettingsCustomOptimiser

Joint

to read from proprioception and then submit as motor sample

FieldTypeLabelDescription
Namestring
TypeJoint.JointTypeEnum
Positionfloat
Velocityfloat
Accelerationfloat
Torquefloat
Minfloat
Maxfloat
Defaultfloat
Temperaturefloat
Healthybool

MotorSample

MotorSample combines all the parts of a motor update into a single message.

FieldTypeLabelDescription
ControlModeMotorSample.ControlModeEnum
LocomotionVelocityTargetLocomotion provides an update for the robot's target velocity of movement within 3D space.
ObjectivesObjectiveCommandrepeatedObjectives holds an array of ObjectiveCommands which define the desired control of the robot's kinematic chains.
ObstaclesObjectrepeatedan array of capsules representing external obstacles to avoid
RawJointsJointrepeatedKinematicChains holds an array of kinematic chains such as head, arms and legs.
WorkspaceReceivedbool
IKSettingsIKOptimiser
GazeTargetGazeTarget

Object

FieldTypeLabelDescription
namestring
OriginTransform
EndAVector3
EndBVector3
Radiusfloat
RatioABfloatdiscard Origin and make EndA EndB relative to global when sending between client and robot

ObjectiveCommand

FieldTypeLabelDescription
TargetEffectorstringName for effector that is the target of this objective
TargetBodyPartstringOptional
ControlModeControllerEnumControlMode specifies how this chain is to be controlled. Position control using PositionTarget. Velocity control using VelocityTarget if ChainType==(ARM_CHAIN_TYPE or LEG_CHAIN_TYPE) (upcoming functionality added for completeness). Torque control using TorqueTarget if ChainType==(ARM_CHAIN_TYPE or LEG_CHAIN_TYPE) (upcoming functionality added for completeness). Torque control gripper maybe?
PoseTargetPoseTargetDefines the position target for the position controller
VelocityTargetVelocityTargetDefines the velocity target for the velocity controller.
TorqueTargetTorqueTargetDefines the torque target for the torque controller.
Enabledbool
CustomNamestring

ObjectiveFeedback

FieldTypeLabelDescription
StatusObjectiveStatusEnum
ControlTypeControllerEnum
TargetTransformTransform
CurrentTransformTransform
EuclideanErrorfloat
PositionErrorVector3
OrientationErrorVector3
ErrorDescriptionstring

PoseTarget

PositionTarget specifies a target spatial orientation and position for the tip of the end effector relative to a provided reference frame. The required joint angles that result in the end effector going to the specified transform are calculated using built-in inverse kinematics. https://en.wikipedia.org/wiki/Inverse_kinematics (opens in a new tab)

FieldTypeLabelDescription
ActionActionEnumDefines the type of action to carry out for this Target. When Action==GO_TO When Action==POINT When Action==GRASP, a gripper command is generated for you if no gripper Objectives are provided in MotorSample.GripperObjective
TargetTypePoseTarget.TargetTypeEnum
TransformTransformTransform describes 3D position and orientation for the target.
ObjectObjectObject defines the external object being interacted with as part of the position target. Used only when Action==POINT or Action==GRASP
MovementDurationMsfloatOptional: MovementDurationMs defines the time allowed for the robot to move to its target transform or target joint angles in milliseconds. Ignored when robot does not support timing information on movements. If it's important to check for the successful execution of a command use proprioception to check.
TargetAccuracyfloat
OptimiserSettingsIKOptimiser

ProprioceptionSample

ProprioceptionSample contains all the information regarding the kinematic state of the robot and relating to the robot's environment

FieldTypeLabelDescription
PartsBodyPartrepeated
EffectorsEffectorrepeated
ObjectsObjectrepeated
RawJointsJointrepeated
WorkspaceByteArraybytes

TorqueTarget

FieldTypeLabelDescription
TranslationalTorqueVector3
RotationalTorqueVector3

VelocityTarget

FieldTypeLabelDescription
TranslationalVelocityVector3
RotationalVelocityVector3

VelocityTargetStatus

ActionEnum

ChainTypeEnum specifies the type of kinematic chain

NameNumberDescription
GOTO0Default: GOTO is a position and orientation objective in relation to a transform
TOUCH1TOUCH is a position and orientation objective in relation to a capsule that explicitly touches surface of capsule
POINT2POINT is a position and orientation objective with a distance_from modifier.
LOOK_AT3Look at is an orientation objective to look at a target transform or capsule. Requires a camera on the limb or gripper
GRASP4GRASP can only be sent to a gripper and results in a GOTO for the upstream effector accompanied by a grasp by the gripper

BodyPart.BodyPartTypeEnum

NameNumberDescription
ROOT0
LIMB1
GRIPPER2

CustomOptimiser.OptimiserMethodEnum

NameNumberDescription
BOUNDED_BFGS0
BFGS1
LBFGS2
GRAD3
CG4
NM5

GazeTarget.TargetTypeEnum

NameNumberDescription
ABSOLUTE0
RELATIVE1

GripperModeEnum

GripperModeEnum specifies the type of control to be used by the gripper

NameNumberDescription
PERCENTAGE_MODE0Defines that the information stored for each digit is a float range of 0 (fully open) to 1 (fully closed)
TRANSFORM_MODE_WRT_WRIST1Defines that the information stored for each digit is a distance from fingertip to palm. This information is used by IK to create a robot agnostic solution that can generate a solution independent of gripper joint configuration
TRANSFORM_MODE_WRT_CAPSULE2
TRANSFORM_MODE_WRT_CUSTOM_REF3
JOINT_MODE4

IKOptimiser.OptimiserPreset

NameNumberDescription
LOW_LATENCY0
HIGH_ACCURACY1
BALANCED2
CUSTOM3

Joint.JointTypeEnum

JointTypeEnum designates the type of joint

NameNumberDescription
FIXED0Default: Joint is a revolute joint that moves in a circular motion and has a max and min angle
LINEAR_PRISMATIC1Joint is a linear prismatic joint that moves in a linear motion
REVOLUTE2Joint is a revolute joint that moves in a circular motion without any limits on angle
CONTINUOUS3

MotorSample.ControlModeEnum

ControlModeEnum specifies whether using direct joint control or other controller through objectives

NameNumberDescription
USE_OBJECTIVE0Default: Use objective to control robot movement
USE_DIRECT_JOINTS1Use direct joint angles

PoseTarget.TargetTypeEnum

NameNumberDescription
TRANSFORM0Default:
CAPSULE1

Top

bow_data_octree.proto

OctreeNode

TimeSync enables the synchronization of clocks between devices.

FieldTypeLabelDescription
EffectorLinkstring
RootLinkstring
CenterPoint
MinXfloat
MaxXfloat
MinYfloat
MaxYfloat
MinZfloat
MaxZfloat
ChildrenOctreeNoderepeated
Leafbool
Depthint32
MaxDepthint32
Reachablebool
ValidOctreebool

Point

FieldTypeLabelDescription
Xfloat
yfloat
Zfloat

Workspaces

FieldTypeLabelDescription
WorkspacesOctreeNoderepeated

Top

bow_data.proto

BlobSample

BlobSample provides flexible data type that can be used to define your own messages in a custom communication channel

FieldTypeLabelDescription
BytesArraybytesrepeatedBytesArray holds an array of bytes.
IntArrayint64repeatedIntArray stores an array of integers.
FloatArrayfloatrepeatedFloatArray contains an array of floating-point numbers.
StringstringString stores a text string.
TransformTransformTransform specifies a spatial orientation and position in a 3D space.

Recording

MotorArray is a collection of MotorSamples, each accompanied by a timestamp, providing a time-ordered set of robot states. This is the data type for a recording.

FieldTypeLabelDescription
ImageSamplesImageSamplesrepeatedSamples contains an array of MotorSamples, each capturing a unique state of the robot's motors.
AudioSamplesAudioSamplesrepeated
ProprioceptionSamplesProprioceptionSamplerepeated
TactileSamplesTactileSamplesrepeated
MotorSamplesMotorSamplerepeated
VoiceSamplesAudioSamplesrepeated
SpeechSamplesStringSamplerepeated
ExteroceptionSamplesExteroceptionSamplerepeated
InteroceptionSamplesInteroceptionSamplerepeated
OctreeSamplesOctreeNoderepeated
Tstampint64repeatedTstamp holds an array of timestamps in milliseconds

StringSample

StringSample encapsulates a single string-based data sample.

FieldTypeLabelDescription
DatastringData contains the string value of the sample.

TimeSync

TimeSync enables the synchronization of clocks between devices.

FieldTypeLabelDescription
TOrigin_0int64TOrigin_0 is the time on the originating device when the sync request is first made
TReceiverint64TReceiver is the time on the receiving device when the sync request is received
TOrigin_1int64TOrigin_1 is the time on the originating device when the sync response is received
ReturnTripboolReturnTrip signifies if the synchronization request has made a round trip

ColorChannelOrder

ColorChannelOrder identifies the color order requested for the texture being memory mapped back the core as part of UpdateTexture. Every pixel is 32bit - 8 bits per channel

NameNumberDescription
RGBA320Default: Red Green Blue
BGRA321Blue Green Red

Top

bow_data_tactile.proto

TactileSample

TactileSample captures data about a single tactile interaction or sensor reading.

FieldTypeLabelDescription
SourcestringSource identifies the tactile sensor that provided the data.
LocationTagRelativeToEnumLocationTag specifies the location on the robot where the sensor is mounted.
DatabytesData contains the raw tactile data.
DataShapeuint32repeatedDataShape provides the dimensions of the tactile data array.
TactileTypeTactileSample.TactileTypeEnumTactileType specifies the type of tactile interaction being captured.
CompressionTactileSample.CompressionFormatEnumCompression indicates the tactile data compression format.
ClassifiedTexturestringClassifiedTexture offers a qualitative description of a detected texture.
FloatDatafloatrepeatedFloatData can contain additional floating-point data related to the tactile sample.
TransformTransformTransform gives the spatial orientation and position of the sensor
NewDataFlagboolNewDataFlag indicates whether the data sample is new or not.

TactileSamples

TactileSamples is a container for multiple instances of tactile data samples.

FieldTypeLabelDescription
SamplesTactileSamplerepeatedSamples is an array of TactileSample messages, each providing detailed information about different types of tactile experiences.

TactileSample.CompressionFormatEnum

CompressionFormatEnum lists available formats for tactile data compression.

NameNumberDescription
RAW0Default: No compression

TactileSample.TactileTypeEnum

TactileTypeEnum enumerates the types of tactile interactions that can be captured.

NameNumberDescription
UNDEFINED0Default: Undefined tactile type
PRESSURE1PRESSURE is a 1D float data type of range [0,1] with 1 item per sensor
VIBRATION2VIBRATION is a 1D float data type of range [0,1] with 1 item per sensor
TEXTURE3TEXTURE represents a classified texture provided as a string
FORCE_FEEDBACK4FORCE_FEEDBACK is a 1D float data type of range [0,1] with 1 item per sensor
TRIAXIAL5TRIAXIAL is a 3D float data type of range [0,1] with 3 items per sensor

Top

bow_data_vision.proto

ImageSample

ImageSample contains various information related to a single image or frame.

FieldTypeLabelDescription
SourcestringSource identifies the origin of the image, such as a camera name or sensor ID.
DatabytesData holds the image information in bytes.
DataShapeuint32repeatedDataShape provides the dimensions of the Data array, useful for reshaping the byte array back into an image.
CompressionImageSample.CompressionFormatEnumCompression indicates the algorithm used to compress the image.
ImageTypeImageSample.ImageTypeEnumImageType specifies the kind of image (RGB, Depth, etc.)
TransformTransformTransform represents the spatial positioning of the camera or sensor at the time the image was captured.
FrameNumberuint64Optional: FrameNumber is a unique identifier for this frame.
DesignationStereoDesignationEnumDesignation pertains to the role of the image in a stereo pair, if applicable.
HFOVfloatOptional: HFOV is the horizontal field of view of the camera in degrees
VFOVfloatOptional: VFOV is the vertical field of view of the camera in degrees.
NewDataFlagboolNewDataFlag indicates whether this sample contains new information since the last capture.

ImageSamples

ImageSamples holds an array of ImageSample objects, each capturing a specific image or frame at a given point in time and with a specific transform

FieldTypeLabelDescription
SamplesImageSamplerepeatedSamples is an array of ImageSample objects.

ImageSample.CompressionFormatEnum

CompressionFormatEnum defines the compression currently in use for this image

NameNumberDescription
H2640h264 compression
VP81Default: vp8 compression
VP92vp9 compression
JPG3jpeg compression
RAW4no compression
H2655h265 compression

ImageSample.ImageTypeEnum

ImageTypeEnum defines the type of image or sensory data.

NameNumberDescription
RGB0Default: Standard red-green-blue image in YUV422 format
DEPTH1Depth map
STEREO2Stereoscopic image
INFRARED3Infrared image

Scalar Value Types

.proto TypeNotesC++JavaPythonGoC#PHPRuby
doubledoubledoublefloatfloat64doublefloatFloat
floatfloatfloatfloatfloat32floatfloatFloat
int32Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint32 instead.int32intintint32intintegerBignum or Fixnum (as required)
int64Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint64 instead.int64longint/longint64longinteger/stringBignum
uint32Uses variable-length encoding.uint32intint/longuint32uintintegerBignum or Fixnum (as required)
uint64Uses variable-length encoding.uint64longint/longuint64ulonginteger/stringBignum or Fixnum (as required)
sint32Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int32s.int32intintint32intintegerBignum or Fixnum (as required)
sint64Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int64s.int64longint/longint64longinteger/stringBignum
fixed32Always four bytes. More efficient than uint32 if values are often greater than 2^28.uint32intintuint32uintintegerBignum or Fixnum (as required)
fixed64Always eight bytes. More efficient than uint64 if values are often greater than 2^56.uint64longint/longuint64ulonginteger/stringBignum
sfixed32Always four bytes.int32intintint32intintegerBignum or Fixnum (as required)
sfixed64Always eight bytes.int64longint/longint64longinteger/stringBignum
boolboolbooleanbooleanboolboolbooleanTrueClass/FalseClass
stringA string must always contain UTF-8 encoded or 7-bit ASCII text.stringStringstr/unicodestringstringstringString (UTF-8)
bytesMay contain any arbitrary sequence of bytes.stringByteStringstr[]byteByteStringstringString (ASCII-8BIT)