BOW Data Messages
BOW Data Messages Reference Documentation
Protocol Documentation
bow_data_audio.proto
AudioSample
AudioSample contains a single packet of audio data from a single source
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source indicates the origin of the audio data, such as a specific microphone. | |
| Data | bytes | Data contains the raw or compressed audio data. | |
| Channels | uint32 | Channels specifies the number of audio channels. | |
| SampleRate | uint64 | SampleRate indicates the number of samples per second. | |
| NumSamples | uint64 | NumSamples provides the total number of audio samples in the Data field. | |
| Compression | AudioSample.CompressionFormatEnum | Compression specifies the audio compression format used. | |
| Transform | Transform | Transform provides the spatial location of the audio source, if applicable. | |
| Designation | StereoDesignationEnum | Designation 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.
| Field | Type | Label | Description | 
|---|---|---|---|
| Samples | AudioSample | repeated | Samples is an array of AudioSample messages, each containing a sample of audio data from different sources | 
AudioSample.CompressionFormatEnum
CompressionFormatEnum lists available audio compression formats.
| Name | Number | Description | 
|---|---|---|
| RAW | 0 | Default: No compression | 
| SPEEX | 1 | Compressed in Speex formats | 
bow_data_common.proto
Environment
Environment provides temperature, pressure and humidity readings.
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the origin of the data, such as a the name or sensor ID. | |
| Type | Environment.SensorTypeEnum | Type identifies the type of sensor as per SensorTypeEnum. | |
| Value | float | Value for the sensor in SI units | |
| Transform | Transform | Transform for the environment sensor | 
Float32Array
Float32Array is a container for an array of floating-point numbers.
| Field | Type | Label | Description | 
|---|---|---|---|
| Data | float | repeated | Data is an array of 32-bit floating-point numbers. | 
Int64Array
Int64Array is a container for an array of 64-bit integers.
| Field | Type | Label | Description | 
|---|---|---|---|
| Data | int64 | repeated | Data is an array of 64-bit integers. | 
Quaternion
Quaternion contains the components of a normalised quaternion that can be used to describe a rotation.
| Field | Type | Label | Description | 
|---|---|---|---|
| QuatX | float | X component of the normalised quaternion | |
| QuatY | float | Y component of the normalised quaternion | |
| QuatZ | float | Z component of the normalised quaternion | |
| QuatW | float | W component of the normalised quaternion | 
Transform
Transform captures a spatial point and orientation in Cartesian coordinates.
| Field | Type | Label | Description | 
|---|---|---|---|
| Position | Vector3 | Position 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. | |
| EulerAngles | Vector3 | EulerAngles use a Vector3 to define rotation through specific angles, in units designated by AngleUnits. | |
| LinkName | string | Optional: LocationTag identifies the origin point to which the transform is relative. | |
| Part | string | 
Vector3
Vector3 contains three components expected for a vector in 3D cartesian space
| Field | Type | Label | Description | 
|---|---|---|---|
| X | float | X component of the vector | |
| Y | float | Y component of the vector | |
| Z | float | Z component of the vector | 
ControllerEnum
ControlModeEnum specifies the controller currently applied to a specific kinematic chain
| Name | Number | Description | 
|---|---|---|
| POSITION_CONTROLLER | 0 | Default: POSITION_CONTROL uses inverse kinematics to control the position and orientation of the end effector at the end of the kinematic chain. | 
| VELOCITY_CONTROLLER | 1 | VELOCITY_CONTROL is not currently available. (Upcoming functionality) | 
| TORQUE_CONTROLLER | 2 | TORQUE_CONTROL is not currently available. (Upcoming functionality) | 
Environment.SensorTypeEnum
| Name | Number | Description | 
|---|---|---|
| Temperature | 0 | |
| Pressure | 1 | |
| Humidity | 2 | 
ObjectiveStatusEnum
| Name | Number | Description | 
|---|---|---|
| NO_OBJECTIVE | 0 | Default: No objective to provide a status for | 
| PLANNING | 1 | Motion plan is being created | 
| IN_PROGRESS | 2 | Objective is currently being executed | 
| COLLISION_ERROR | 3 | Objective execution stopped due to collision | 
| ERROR | 4 | Objective execution stopped due to error | 
| WARNING | 5 | Warning raised | 
| FINISHED | 6 | Objective finished successfully | 
RelativeToEnum
RelativeToEnum marks specific points on the robot for spatial reference.
| Name | Number | Description | 
|---|---|---|
| BASE | 0 | Default: Base indicates the robot's contact point with the floor. | 
| HEAD | 1 | Head marks the robot's primary vision point, often where the main camera is located. | 
| END_EFFECTOR | 2 | End_Effector identifies the Terminal point of an articulated assembly. | 
| END_EFFECTOR_LEFT | 3 | Identical to End_Effector but specifies the main articulated assembly on the left side of the robot. | 
| END_EFFECTOR_RIGHT | 4 | Identical to End_Effector but specifies the main articulated assembly on the right side of the robot. | 
| TORSO | 5 | Torso 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
| Name | Number | Description | 
|---|---|---|
| NONE | 0 | Default: Camera functions independently, not as part of a stereo pair. | 
| LEFT | 1 | Camera operates as the left component in a stereo pair. | 
| RIGHT | 2 | Camera operates as the right component in a stereo pair. | 
bow_data_exteroception.proto
Compass
Compass provides the magnetic field along up to 3 axis
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the origin of the data, such as a the name or sensor ID. | |
| Mag | Vector3 | Mag represents the measured components of the magnetic field along each axis | |
| Transform | Transform | Transform provides the spatial positioning of the compass | 
ExteroceptionSample
Exteroception contains sensor reading related to awareness of the surrounding environment
| Field | Type | Label | Description | 
|---|---|---|---|
| Lidar | Lidar | repeated | Optional: Lidar provides an array of range values representing the distances to objects at varying angles from a point | 
| Range | Range | repeated | Optional: Range provides a distance or binary present/not present signal representing the output of a range sensor | 
| Imu | IMU | repeated | Optional: Imu provides the 3D acceleration, orientation, and gravitational forces experienced at different positions on a robot's body | 
| Gps | GPS | Optional: Gps provides the global position of the robot, if available | |
| Compass | Compass | Optional: Compass provides the magnetic field along up to 3 axis | |
| Env | Environment | repeated | Optional: Environment provides temperature, pressure and humidity readings. | 
| Light | Light | repeated | Optional: Light provides a measurement of light/brightness at the location of the sensor | 
GPS
GPS captures geographic positioning data.
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the origin of the data, such as a the name or sensor ID. | |
| Latitude | float | Latitude in decimal degrees | |
| Longitude | float | Longitude in decimal degrees | |
| Elevation | float | Elevation in meters above sea level | |
| Time | string | Timestamp of the GPS sample | |
| Transform | Transform | Transform for the GPS sample | 
IMU
IMU (Inertial Measurement Unit) captures the sensor data needed to determine an object's orientation, velocity, and gravitational forces.
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the origin of the data, such as a the name or sensor ID. | |
| Gyro | Vector3 | Gyro represents angular velocity measured in radians per second along X, Y, and Z axes. | |
| Acc | Vector3 | Acc signifies linear acceleration in meters per second squared along X, Y, and Z axes. | |
| Orientation | Vector3 | Optional: Returns the angular position of the IMU. | |
| Transform | Transform | Transform provides a reference frame for the IMU data. | |
| HasAcc | bool | ||
| HasGyro | bool | 
Lidar
Lidar provides an array of range values representing the distances to objects at varying angles from a central point
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the origin of the data, such as a the name or sensor ID. | |
| Data | float | repeated | Data provides the distance to an obstacle within an angular segment of size defined by spatial resolution. | 
| DataShape | uint32 | repeated | DataShape provides the dimensions of the Data array. Height is 1 for 2D Lidar or bigger for 3D Lidar | 
| HorizontalAngularResolution | float | HorizontalAngularResolution specifies the granularity of the lidar data, the angle between each sample for the horizontal axis. | |
| VerticalAngularResolution | float | HorizontalAngularResolution specifies the granularity of the lidar data, the angle between each sample for the horizontal axis. | |
| HorizontalStartAngle | float | Optional: Start provides the start angle of the horizontal scan, if not populated assumed to be 0 degrees | |
| HorizontalEndAngle | float | End provides the end angle of the horizontal scan, if not populated assumed to be 360 degrees | |
| VerticalStartAngle | float | Optional: Start provides the start angle of the vertical scan, if not populated assumed to be 0 degrees | |
| VerticalEndAngle | float | End provides the end angle of the horizontal scan, if not populated assumed to be 360 degrees | |
| ScanDuration | int64 | Time taken to complete scan in milliseconds | |
| TimeBetweenScans | int64 | Time between measurement intervals in milliseconds | |
| Transform | Transform | Transform represents the spatial positioning of the lidar sensor at the time the data was captured. | |
| NewDataFlag | bool | Flag which allows pre-setting of parameters awaiting new data | 
Light
Light provides a measurement of light/brightness at the location of the sensor
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the origin of the data, such as a the name or sensor ID. | |
| Data | float | Data provides the light measurement in the provided units | |
| Min | float | Min provides the minimum value for which readings from the sensor are valid | |
| Max | float | Max provides the maximum value for which readings from the sensor are valid | |
| Unit | Light.LightUnitEnum | Unit provides the unit of the light measurement | |
| Transform | Transform | Transform provides the spatial positioning of the sensor | 
Range
Range provides a distance or (present/not present) signal representing the output of a range sensor
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the origin of the data, such as a the name or sensor ID. | |
| Data | float | Data provides the distance to the nearest object in the field of view of the sensor | |
| Min | float | Min provides the minimum range at which readings from the sensor are valid | |
| Max | float | Max provides the maximum range at which readings from the sensor are valid | |
| FOV | float | FOV provides the field of view of the range sensor as an angle | |
| SensorType | Range.SensorTypeEnum | SensorType provides the type of sensor which determines the expected output | |
| OperationType | Range.OperationTypeEnum | OperationType provides the mechanism which the sensor uses for its operation, i.e. light, sound, mechanical. | |
| Transform | Transform | Transform represents the spatial positioning of the range sensor at the time the data was captured. | 
Light.LightUnitEnum
| Name | Number | Description | 
|---|---|---|
| Irradiance | 0 | |
| Illuminance | 1 | |
| Normalised | 2 | 
Range.OperationTypeEnum
An enum defining physical mechanism used by the sensor
| Name | Number | Description | 
|---|---|---|
| Ultrasound | 0 | Sensor uses ultrasound for ranging, i.e. sonar | 
| Infrared | 1 | Sensor uses infrared light for ranging, i.e. ToF | 
| Mechanical | 2 | Sensor is a mechanical switch, i.e. cliff sensor | 
| Laser | 3 | Sensor is a laser ranging device i.e single point lidar | 
Range.SensorTypeEnum
An enum defining the type of range sensor
| Name | Number | Description | 
|---|---|---|
| Distance | 0 | Default: Sensor will return a range value | 
| Proximity | 1 | Sensor will return a confidence value of object exists/doesn't exist | 
bow_data_interoception.proto
Battery
| Field | Type | Label | Description | 
|---|---|---|---|
| Voltage | float | Voltage provides the voltage reading across the battery | |
| Current | float | Current provides the current draw in Amps | |
| Charge | float | Charge provides charge in the battery in Amp Hours | |
| Percentage | float | Provides the percentage charge of the battery remaining | |
| Present | bool | True if the battery is connected, otherwise False | |
| SupplyStatus | Battery.SupplyStatusEnum | An enum providing the status of the robots power supply/battery charger | 
InteroceptionSample
Interoception contains sensor readings related to the internal state of the robot
| Field | Type | Label | Description | 
|---|---|---|---|
| Env | Environment | repeated | Optional: Env provides temperature, pressure and humidity readings from the inside of the robot | 
| battery | Battery | Battery provides the current state of the battery | |
| Error | string | repeated | A list of any provided error messages or codes | 
Battery.SupplyStatusEnum
| Name | Number | Description | 
|---|---|---|
| Unknown | 0 | |
| Charging | 1 | |
| Discharging | 2 | |
| Not_Charging | 3 | |
| Complete | 4 | 
bow_data_motor.proto
BodyPart
EndEffector defines an update to be sent to an articulated assembly, such as an arm or a leg
| Field | Type | Label | Description | 
|---|---|---|---|
| Name | string | ||
| Type | BodyPartTypeEnum | ||
| RootLink | string | ||
| Effectors | Effector | repeated | |
| Parent | string | 
CustomOptimiser
| Field | Type | Label | Description | 
|---|---|---|---|
| OptimiserMethod | CustomOptimiser.OptimiserMethodEnum | ||
| Iterations | int32 | ||
| UseEvolution | bool | 
Effector
| Field | Type | Label | Description | 
|---|---|---|---|
| EffectorLinkName | string | ||
| EndTransform | Transform | ||
| RootTransform | Transform | ||
| Reach | float | ||
| JointArray | Joint | repeated | JointArray 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 | 
| AvailableActions | ActionEnum | repeated | |
| Workspace | OctreeNode | ||
| Objectives | ObjectiveFeedback | repeated | |
| IsControllable | bool | ||
| Type | BodyPartTypeEnum | 
GazeTarget
| Field | Type | Label | Description | 
|---|---|---|---|
| GazeVector | Vector3 | ||
| VectorType | GazeTarget.TargetTypeEnum | 
Gripper
Gripper outlines the configuration of a hand-like gripper in terms of each finger's position.
| Field | Type | Label | Description | 
|---|---|---|---|
| GripperControlMode | GripperModeEnum | ||
| HandMapPercentage | HandMapPercentage | ||
| HandMapTransform | HandMapTransform | ||
| JointArray | Joint | repeated | 
GripperStatus
HandMapPercentage
| Field | Type | Label | Description | 
|---|---|---|---|
| Thumb | float | Thumb specifies the % closed for the thumb [0-1] or distance of thumb-tip to palm. | |
| Index | float | Index specifies the % closed for the index finger [0-1] or distance of index fingertip to palm. | |
| Middle | float | Middle specifies the % closed for the middle finger [0-1] or distance of middle fingertip to palm. | |
| Ring | float | Ring specifies the % closed for the ring finger [0-1] or distance of ring fingertip to palm. | |
| Pinky | float | Pinky specifies the % closed for the pinky finger [0-1] or distance of pinky fingertip to palm. | |
| FingerAdduction | float | FingerAddiction specifies the spread of the fingers as a % [0-1]. Not used in DISTANCE_IK mode. | |
| ThumbOpposition | float | ThumbOpposition specifies the opposition of the thumb as a % [0-1]. Not used in DISTANCE_IK mode. | 
HandMapTransform
| Field | Type | Label | Description | 
|---|---|---|---|
| CustomRef | Transform | ||
| Thumb | Transform | ||
| Index | Transform | ||
| Middle | Transform | ||
| Ring | Transform | ||
| Pinky | Transform | ||
| TargetObject | Object | 
IKOptimiser
| Field | Type | Label | Description | 
|---|---|---|---|
| Preset | IKOptimiser.OptimiserPreset | ||
| CustomSettings | CustomOptimiser | 
Joint
to read from proprioception and then submit as motor sample
| Field | Type | Label | Description | 
|---|---|---|---|
| Name | string | ||
| Type | Joint.JointTypeEnum | ||
| Position | float | ||
| Velocity | float | ||
| Acceleration | float | ||
| Torque | float | ||
| Min | float | ||
| Max | float | ||
| Default | float | ||
| Temperature | float | ||
| Healthy | bool | ||
| Mimic | bool | ||
| MaxVelocity | float | ||
| MaxAcceleration | float | ||
| MaxTorque | float | 
MotorSample
MotorSample combines all the parts of a motor update into a single message.
| Field | Type | Label | Description | 
|---|---|---|---|
| ControlMode | MotorSample.ControlModeEnum | ||
| Locomotion | VelocityTarget | Locomotion provides an update for the robot's target velocity of movement within 3D space. | |
| Objectives | ObjectiveCommand | repeated | Objectives holds an array of ObjectiveCommands which define the desired control of the robot's kinematic chains. | 
| Obstacles | Object | repeated | an array of capsules representing external obstacles to avoid | 
| RawJoints | Joint | repeated | KinematicChains holds an array of kinematic chains such as head, arms and legs. | 
| WorkspaceReceived | bool | ||
| IKSettings | IKOptimiser | ||
| GazeTarget | GazeTarget | ||
| GripperObjective | Gripper | ||
| GaitSettings | QuadGait | 
Object
| Field | Type | Label | Description | 
|---|---|---|---|
| name | string | ||
| Origin | Transform | ||
| EndA | Vector3 | ||
| EndB | Vector3 | ||
| Radius | float | ||
| RatioAB | float | discard Origin and make EndA EndB relative to global when sending between client and robot | 
ObjectiveCommand
| Field | Type | Label | Description | 
|---|---|---|---|
| TargetEffector | string | Name for effector that is the target of this objective | |
| TargetBodyPart | string | Optional | |
| ControlMode | ControllerEnum | ControlMode 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? | |
| PoseTarget | PoseTarget | Defines the position target for the position controller | |
| VelocityTarget | VelocityTarget | Defines the velocity target for the velocity controller. | |
| TorqueTarget | TorqueTarget | Defines the torque target for the torque controller. | |
| Enabled | bool | ||
| CustomName | string | 
ObjectiveFeedback
| Field | Type | Label | Description | 
|---|---|---|---|
| Status | ObjectiveStatusEnum | ||
| ControlType | ControllerEnum | ||
| TargetTransform | Transform | ||
| CurrentTransform | Transform | ||
| EuclideanError | float | ||
| PositionError | Vector3 | ||
| OrientationError | Vector3 | ||
| ErrorDescription | string | 
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
| Field | Type | Label | Description | 
|---|---|---|---|
| Action | ActionEnum | Defines 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 | |
| TargetType | PoseTarget.TargetTypeEnum | ||
| TargetScheduleType | PoseTarget.SchedulerEnum | ||
| Transform | Transform | Transform describes 3D position and orientation for the target. | |
| Object | Object | Object defines the external object being interacted with as part of the position target. Used only when Action==POINT or Action==GRASP | |
| MovementDurationMs | float | Optional: 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. | |
| TargetAccuracy | float | ||
| OptimiserSettings | IKOptimiser | 
ProprioceptionSample
ProprioceptionSample contains all the information regarding the kinematic state of the robot and relating to the robot's environment
| Field | Type | Label | Description | 
|---|---|---|---|
| Parts | BodyPart | repeated | |
| Effectors | Effector | repeated | |
| Objects | Object | repeated | |
| RawJoints | Joint | repeated | |
| WorkspaceByteArray | bytes | 
QuadGait
| Field | Type | Label | Description | 
|---|---|---|---|
| UseCustomGait | bool | ||
| CommonXTranslation | float | ||
| SwingHeight | float | ||
| StanceDepth | float | ||
| StanceDuration | float | ||
| SwingDuration | float | ||
| NominalHeight | float | ||
| GaitOrientation | Vector3 | 
TorqueTarget
VelocityTarget
VelocityTargetStatus
ActionEnum
ChainTypeEnum specifies the type of kinematic chain
| Name | Number | Description | 
|---|---|---|
| GOTO | 0 | Default: GOTO is a position and orientation objective in relation to a transform | 
| TOUCH | 1 | TOUCH is a position and orientation objective in relation to a capsule that explicitly touches surface of capsule | 
| POINT | 2 | POINT is a position and orientation objective with a distance_from modifier. | 
| LOOK_AT | 3 | Look at is an orientation objective to look at a target transform or capsule. Requires a camera on the limb or gripper | 
| GRASP | 4 | GRASP can only be sent to a gripper and results in a GOTO for the upstream effector accompanied by a grasp by the gripper | 
BodyPartTypeEnum
| Name | Number | Description | 
|---|---|---|
| ROOT | 0 | |
| LIMB | 1 | |
| GRIPPER | 2 | |
| EFFECTOR | 3 | 
CustomOptimiser.OptimiserMethodEnum
| Name | Number | Description | 
|---|---|---|
| BOUNDED_BFGS | 0 | |
| BFGS | 1 | |
| LBFGS | 2 | |
| GRAD | 3 | |
| CG | 4 | |
| NM | 5 | 
GazeTarget.TargetTypeEnum
| Name | Number | Description | 
|---|---|---|
| ABSOLUTE | 0 | |
| RELATIVE | 1 | 
GripperModeEnum
GripperModeEnum specifies the type of control to be used by the gripper
| Name | Number | Description | 
|---|---|---|
| PERCENTAGE_MODE | 0 | Defines that the information stored for each digit is a float range of 0 (fully open) to 1 (fully closed) | 
| TRANSFORM_MODE_WRT_WRIST | 1 | Defines 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_CAPSULE | 2 | |
| TRANSFORM_MODE_WRT_CUSTOM_REF | 3 | |
| JOINT_MODE | 4 | 
IKOptimiser.OptimiserPreset
| Name | Number | Description | 
|---|---|---|
| LOW_LATENCY | 0 | |
| HIGH_ACCURACY | 1 | |
| BALANCED | 2 | |
| CUSTOM | 3 | 
Joint.JointTypeEnum
JointTypeEnum designates the type of joint
| Name | Number | Description | 
|---|---|---|
| FIXED | 0 | Default: Joint is a fixed and immovable joint | 
| LINEAR_PRISMATIC | 1 | Joint is a linear prismatic joint that moves in a linear motion | 
| REVOLUTE | 2 | Joint is a revolute joint that moves in a circular motion and has a max and min angle | 
| CONTINUOUS | 3 | Joint is a continuous joint that moves in a circular motion without any limits on angle | 
MotorSample.ControlModeEnum
ControlModeEnum specifies whether using direct joint control or other controller through objectives
| Name | Number | Description | 
|---|---|---|
| USE_OBJECTIVE | 0 | Default: Use objective to control robot movement | 
| USE_DIRECT_JOINTS | 1 | Use direct joint angles | 
PoseTarget.SchedulerEnum
| Name | Number | Description | 
|---|---|---|
| SEQUENTIAL | 0 | Default: | 
| INSTANTANEOUS | 1 | 
PoseTarget.TargetTypeEnum
| Name | Number | Description | 
|---|---|---|
| TRANSFORM | 0 | Default: | 
| CAPSULE | 1 | 
bow_data_octree.proto
OctreeNode
TimeSync enables the synchronization of clocks between devices.
| Field | Type | Label | Description | 
|---|---|---|---|
| EffectorLink | string | ||
| RootLink | string | ||
| Center | Point | ||
| MinX | float | ||
| MaxX | float | ||
| MinY | float | ||
| MaxY | float | ||
| MinZ | float | ||
| MaxZ | float | ||
| Children | OctreeNode | repeated | |
| Leaf | bool | ||
| Depth | int32 | ||
| MaxDepth | int32 | ||
| Reachable | bool | ||
| ValidOctree | bool | 
Point
Workspaces
| Field | Type | Label | Description | 
|---|---|---|---|
| Workspaces | OctreeNode | repeated | 
bow_data.proto
BlobSample
BlobSample provides flexible data type that can be used to define your own messages in a custom communication channel
| Field | Type | Label | Description | 
|---|---|---|---|
| BytesArray | bytes | repeated | BytesArray holds an array of bytes. | 
| IntArray | int64 | repeated | IntArray stores an array of integers. | 
| FloatArray | float | repeated | FloatArray contains an array of floating-point numbers. | 
| String | string | String stores a text string. | |
| Transform | Transform | Transform 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.
| Field | Type | Label | Description | 
|---|---|---|---|
| ImageSamples | ImageSamples | repeated | Samples contains an array of MotorSamples, each capturing a unique state of the robot's motors. | 
| AudioSamples | AudioSamples | repeated | |
| ProprioceptionSamples | ProprioceptionSample | repeated | |
| TactileSamples | TactileSamples | repeated | |
| MotorSamples | MotorSample | repeated | |
| VoiceSamples | AudioSamples | repeated | |
| SpeechSamples | StringSample | repeated | |
| ExteroceptionSamples | ExteroceptionSample | repeated | |
| InteroceptionSamples | InteroceptionSample | repeated | |
| OctreeSamples | OctreeNode | repeated | |
| Tstamp | int64 | repeated | Tstamp holds an array of timestamps in milliseconds | 
StringSample
StringSample encapsulates a single string-based data sample.
| Field | Type | Label | Description | 
|---|---|---|---|
| Data | string | Data contains the string value of the sample. | 
TimeSync
TimeSync enables the synchronization of clocks between devices.
| Field | Type | Label | Description | 
|---|---|---|---|
| TOrigin_0 | int64 | TOrigin_0 is the time on the originating device when the sync request is first made | |
| TReceiver | int64 | TReceiver is the time on the receiving device when the sync request is received | |
| TOrigin_1 | int64 | TOrigin_1 is the time on the originating device when the sync response is received | |
| ReturnTrip | bool | ReturnTrip 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
| Name | Number | Description | 
|---|---|---|
| RGBA32 | 0 | Default: Red Green Blue | 
| BGRA32 | 1 | Blue Green Red | 
bow_data_tactile.proto
TactileSample
TactileSample captures data about a single tactile interaction or sensor reading.
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the tactile sensor that provided the data. | |
| LocationTag | RelativeToEnum | LocationTag specifies the location on the robot where the sensor is mounted. | |
| Data | bytes | Data contains the raw tactile data. | |
| DataShape | uint32 | repeated | DataShape provides the dimensions of the tactile data array. | 
| TactileType | TactileSample.TactileTypeEnum | TactileType specifies the type of tactile interaction being captured. | |
| Compression | TactileSample.CompressionFormatEnum | Compression indicates the tactile data compression format. | |
| ClassifiedTexture | string | ClassifiedTexture offers a qualitative description of a detected texture. | |
| FloatData | float | repeated | FloatData can contain additional floating-point data related to the tactile sample. | 
| Transform | Transform | Transform gives the spatial orientation and position of the sensor | |
| NewDataFlag | bool | NewDataFlag indicates whether the data sample is new or not. | 
TactileSamples
TactileSamples is a container for multiple instances of tactile data samples.
| Field | Type | Label | Description | 
|---|---|---|---|
| Samples | TactileSample | repeated | Samples 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.
| Name | Number | Description | 
|---|---|---|
| RAW | 0 | Default: No compression | 
TactileSample.TactileTypeEnum
TactileTypeEnum enumerates the types of tactile interactions that can be captured.
| Name | Number | Description | 
|---|---|---|
| UNDEFINED | 0 | Default: Undefined tactile type | 
| PRESSURE | 1 | PRESSURE is a 1D float data type of range [0,1] with 1 item per sensor | 
| VIBRATION | 2 | VIBRATION is a 1D float data type of range [0,1] with 1 item per sensor | 
| TEXTURE | 3 | TEXTURE represents a classified texture provided as a string | 
| FORCE_FEEDBACK | 4 | FORCE_FEEDBACK is a 1D float data type of range [0,1] with 1 item per sensor | 
| TRIAXIAL | 5 | TRIAXIAL is a 3D float data type of range [0,1] with 3 items per sensor | 
bow_data_vision.proto
ImageSample
ImageSample contains various information related to a single image or frame.
| Field | Type | Label | Description | 
|---|---|---|---|
| Source | string | Source identifies the origin of the image, such as a camera name or sensor ID. | |
| Data | bytes | Data holds the image information in bytes. | |
| DataShape | uint32 | repeated | DataShape provides the dimensions of the Data array, useful for reshaping the byte array back into an image. | 
| Compression | ImageSample.CompressionFormatEnum | Compression indicates the algorithm used to compress the image. | |
| ImageType | ImageSample.ImageTypeEnum | ImageType specifies the kind of image (RGB, Depth, etc.) | |
| Transform | Transform | Transform represents the spatial positioning of the camera or sensor at the time the image was captured. | |
| FrameNumber | uint64 | Optional: FrameNumber is a unique identifier for this frame. | |
| Designation | StereoDesignationEnum | Designation pertains to the role of the image in a stereo pair, if applicable. | |
| HFOV | float | Optional: HFOV is the horizontal field of view of the camera in degrees | |
| VFOV | float | Optional: VFOV is the vertical field of view of the camera in degrees. | |
| NewDataFlag | bool | NewDataFlag indicates whether this sample contains new information since the last capture. | |
| Min | uint32 | ||
| Max | uint32 | 
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
| Field | Type | Label | Description | 
|---|---|---|---|
| Samples | ImageSample | repeated | Samples is an array of ImageSample objects. | 
ImageSample.CompressionFormatEnum
CompressionFormatEnum defines the compression currently in use for this image
| Name | Number | Description | 
|---|---|---|
| H264 | 0 | h264 compression | 
| VP8 | 1 | Default: vp8 compression | 
| VP9 | 2 | vp9 compression | 
| JPG | 3 | jpeg compression | 
| RAW | 4 | no compression | 
| H265 | 5 | h265 compression | 
ImageSample.ImageTypeEnum
ImageTypeEnum defines the type of image or sensory data.
| Name | Number | Description | 
|---|---|---|
| RGB | 0 | Default: Standard red-green-blue image in YUV422 format | 
| DEPTH | 1 | Depth map | 
| STEREO | 2 | Stereoscopic image | 
| INFRARED | 3 | Infrared image |