Skip to content

Protocol Documentation

Table of Contents

Top

rb/api/arm-command.proto

ArmCommand

ArmCommand

ArmCommand-Feedback

ArmCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
joint-position-command-feedbackJointPositionCommand.Feedback
gravity-compensation-command-feedbackGravityCompensationCommand.Feedback
cartesian-command-feedbackCartesianCommand.Feedback
impedance-control-command-feedbackImpedanceControlCommand.Feedback

ArmCommand-Request

ArmCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
joint-position-commandJointPositionCommand.Request
gravity-compensation-commandGravityCompensationCommand.Request
cartesian-commandCartesianCommand.Request
impedance-control-commandImpedanceControlCommand.Request

Top

rb/api/basic-command.proto

CartesianCommand

CartesianCommand

CartesianCommand-Feedback

CartesianCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
tracking-errorsCartesianCommand.TrackingErrorrepeated

CartesianCommand-Request

CartesianCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
minimum-timegoogle.protobuf.Duration
targetsCartesianCommand.SE3PoseTargetrepeated
stop-position-tracking-errorgoogle.protobuf.DoubleValue
stop-orientation-tracking-errorgoogle.protobuf.DoubleValue

CartesianCommand-SE3PoseTarget

CartesianCommand.SE3PoseTarget

FieldTypeLabelDescription
ref-link-namestring
link-namestring
TSE3Pose
linear-velocity-limitgoogle.protobuf.DoubleValue(m/s)
angular-velocity-limitgoogle.protobuf.DoubleValue(rad/s)
acceleration-limit-scalinggoogle.protobuf.DoubleValuedefault.linear-acceleration-limit * acceleration-limit-scaling default.angular-acceleration-limit * acceleration-limit-scaling

(0, 1] |

CartesianCommand-TrackingError

CartesianCommand.TrackingError

FieldTypeLabelDescription
position-errordouble
rotation-errordouble

GravityCompensationCommand

GravityCompensationCommand

GravityCompensationCommand-Feedback

GravityCompensationCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback

GravityCompensationCommand-Request

GravityCompensationCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
onbool

ImpedanceControlCommand

ImpedanceControlCommand

ImpedanceControlCommand-Feedback

ImpedanceControlCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
tracking-errorImpedanceControlCommand.TrackingError

ImpedanceControlCommand-Request

ImpedanceControlCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
ref-link-namestring
link-namestring
TSE3Pose
translation-weightVec3
rotation-weightVec3

ImpedanceControlCommand-TrackingError

ImpedanceControlCommand.TrackingError

FieldTypeLabelDescription
position-errordouble
rotation-errordouble

JogCommand

JogCommand

JogCommand-Feedback

JogCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
target-joint-namestring

JogCommand-Request

JogCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
joint-namestring
velocity-limitgoogle.protobuf.DoubleValue(rad/s) (optional)
acceleration-limitgoogle.protobuf.DoubleValue(rad/s^2) (optional)
absolute-positiondouble(rad)
relative-positiondouble(rad) current position + relative position
one-stepbool5 deg, true is positive move, false is negative move

JointPositionCommand

JointPositionCommand

JointPositionCommand-Feedback

JointPositionCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback

JointPositionCommand-Request

JointPositionCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
minimum-timegoogle.protobuf.Duration
positiondoublerepeated
velocity-limitdoublerepeated
acceleration-limitdoublerepeated
cutoff-frequencygoogle.protobuf.DoubleValue

JointVelocityCommand

JointVelocityCommand

JointVelocityCommand-Feedback

JointVelocityCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback

JointVelocityCommand-Request

JointVelocityCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
minimum-timegoogle.protobuf.Duration
velocitydoublerepeated
acceleration-limitdoublerepeated

OptimalControlCommand

OptimalControlCommand

OptimalControlCommand-CartesianCost

OptimalControlCommand.CartesianCost

FieldTypeLabelDescription
ref-link-namestring
link-namestring
TSE3Pose
translation-weightdoubledefault = 1
rotation-weightdoubledefault = 1

OptimalControlCommand-CenterOfMassCost

OptimalControlCommand.CenterOfMassCost

FieldTypeLabelDescription
ref-link-namestring
poseVec3
weightdoubledefault = 1

OptimalControlCommand-Feedback

OptimalControlCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
total-costdouble
cartesian-costsdoublerepeated
center-of-mass-costdouble
joint-position-costsdoublerepeated

OptimalControlCommand-JointPositionCost

OptimalControlCommand.JointPositionCost

FieldTypeLabelDescription
joint-namestring
target-positiondouble
weightdouble

OptimalControlCommand-Request

OptimalControlCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
cartesian-costsOptimalControlCommand.CartesianCostrepeated
center-of-mass-costOptimalControlCommand.CenterOfMassCost
joint-position-costsOptimalControlCommand.JointPositionCostrepeated
velocity-limit-scalinggoogle.protobuf.DoubleValuevelocity scaling factor: qdot-limit * default.velocity-limit-scaling * velocity-limit-scaling default: 1.0, range: (0, 1]
velocity-tracking-gaingoogle.protobuf.DoubleValuevelocity tracking gain default: default.optimal-control-command.velocity-tracking-gain, range: (0, 1]
stop-costgoogle.protobuf.DoubleValuestop cost default: default.optimal-control-command.stop-cost, range: (0, ∞)
min-delta-costgoogle.protobuf.DoubleValueminimum delta cost range: (0, ∞)
patiencegoogle.protobuf.Int32Valuepatience parameter range: (0, ∞)

RealTimeControlCommand

RealTimeControlCommand

RealTimeControlCommand-Feedback

RealTimeControlCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback

RealTimeControlCommand-Request

RealTimeControlCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
portuint32

SE2VelocityCommand

SE2VelocityCommand

SE2VelocityCommand-Feedback

SE2VelocityCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback

SE2VelocityCommand-Request

SE2VelocityCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
minimum-timegoogle.protobuf.Duration
velocitySE2Velocity
acceleration-limitSE2Velocity

StopCommand

StopCommand

StopCommand-Feedback

StopCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback

StopCommand-Request

StopCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request

Top

rb/api/body-command.proto

BodyCommand

BodyCommand

BodyCommand-Feedback

BodyCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
joint-position-command-feedbackJointPositionCommand.Feedback
optimal-control-command-feedbackOptimalControlCommand.Feedback
gravity-compensation-command-feedbackGravityCompensationCommand.Feedback
cartesian-command-feedbackCartesianCommand.Feedback
body-component-based-command-feedbackBodyComponentBasedCommand.Feedback

BodyCommand-Request

BodyCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
joint-position-commandJointPositionCommand.Request
optimal-control-commandOptimalControlCommand.Request
gravity-compensation-commandGravityCompensationCommand.Request
cartesian-commandCartesianCommand.Request
body-component-based-commandBodyComponentBasedCommand.Request

Top

rb/api/body-component-based-command.proto

BodyComponentBasedCommand

BodyComponentBasedCommand

BodyComponentBasedCommand-Feedback

BodyComponentBasedCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
right-arm-command-feedbackArmCommand.Feedback
left-arm-command-feedbackArmCommand.Feedback
torso-command-feedbackTorsoCommand.Feedback

BodyComponentBasedCommand-Request

BodyComponentBasedCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
right-arm-commandArmCommand.Request
left-arm-commandArmCommand.Request
torso-commandTorsoCommand.Request

Top

rb/api/command-header.proto

CommandHeader

CommandHeader

CommandHeader-Feedback

CommandHeader.Feedback

FieldTypeLabelDescription
finishedbool

CommandHeader-Request

CommandHeader.Request

FieldTypeLabelDescription
control-hold-timegoogle.protobuf.Duration
gravityVec3
inertialsCommandHeader.Request.InertialsEntryrepeated

CommandHeader-Request-InertialsEntry

CommandHeader.Request.InertialsEntry

FieldTypeLabelDescription
keystring
valueInertial

Top

rb/api/component-based-command.proto

ComponentBasedCommand

ComponentBasedCommand

ComponentBasedCommand-Feedback

ComponentBasedCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
mobility-command-feedbackMobilityCommand.Feedback
body-command-feedbackBodyCommand.Feedback
head-command-feedbackHeadCommand.Feedback

ComponentBasedCommand-Request

ComponentBasedCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
mobility-commandMobilityCommand.Request
body-commandBodyCommand.Request
head-commandHeadCommand.Request

Top

rb/api/control-manager.proto

ControlManagerCommandRequest

ControlManagerCommandRequest

FieldTypeLabelDescription
request-headerRequestHeaderRequest header
commandControlManagerCommandRequest.Command
unlimited-mode-enabledgoogle.protobuf.BoolValue

ControlManagerCommandResponse

ControlManagerCommandResponse

FieldTypeLabelDescription
response-headerResponseHeaderResponse header
control-manager-stateControlManagerState

ControlManagerState

ControlManagerState

FieldTypeLabelDescription
stateControlManagerState.State
time-scaledouble
control-stateControlManagerState.ControlState
enabled-joint-idxuint32repeated
unlimited-mode-enabledbool

GetTimeScaleRequest

GetTimeScaleRequest

FieldTypeLabelDescription
request-headerRequestHeaderRequest header

GetTimeScaleResponse

GetTimeScaleResponse

FieldTypeLabelDescription
response-headerResponseHeaderResponse header
time-scaledouble

SetTimeScaleRequest

SetTimeScaleRequest

FieldTypeLabelDescription
request-headerRequestHeaderRequest header
time-scaledouble

SetTimeScaleResponse

SetTimeScaleResponse

FieldTypeLabelDescription
response-headerResponseHeaderResponse header
current-time-scaledouble

ControlManagerCommandRequest-Command

ControlManagerCommandRequest.Command

Control manager command

NameNumberDescription
COMMAND-UNKNOWN0
COMMAND-ENABLE1
COMMAND-DISABLE2
COMMAND-RESET-FAULT3

ControlManagerState-ControlState

ControlManagerState.ControlState

NameNumberDescription
CONTROL-STATE-UNKNOWN0
CONTROL-STATE-IDLE1
CONTROL-STATE-EXECUTING2
CONTROL-STATE-SWITCHING3

ControlManagerState-State

ControlManagerState.State

NameNumberDescription
CONTROL-MANAGER-STATE-UNKNOWN0
CONTROL-MANAGER-STATE-IDLE1
CONTROL-MANAGER-STATE-ENABLED2
CONTROL-MANAGER-STATE-MINOR-FAULT3
CONTROL-MANAGER-STATE-MAJOR-FAULT4

Top

rb/api/control-manager-service.proto

ControlManagerService

ControlManagerService

Method NameRequest TypeResponse TypeDescription
ControlManagerCommandControlManagerCommandRequestControlManagerCommandResponse
GetTimeScaleGetTimeScaleRequestGetTimeScaleResponse
SetTimeScaleSetTimeScaleRequestSetTimeScaleResponse

Top

rb/api/gamepad.proto

Gamepad

Gamepad

FieldTypeLabelDescription
buttonsboolrepeated
joystickdoublerepeated

UploadGamepadDataRequest

UploadGamepadDataRequest

FieldTypeLabelDescription
request-headerRequestHeader
dataGamepad

UploadGamepadDataResponse

UploadGamepadDataResponse

FieldTypeLabelDescription
response-headerResponseHeader

Top

rb/api/gamepad-service.proto

GamepadService

GamepadService

Method NameRequest TypeResponse TypeDescription
UploadGamepadDataGamepad streamUploadGamepadDataResponse

Top

rb/api/geometry.proto

EulerAngleZYX

EulerAngleZYX

FieldTypeLabelDescription
zdouble
ydouble
xdouble

Inertia

Inertia

Inertia tensor components (kg*m^2)

FieldTypeLabelDescription
ixxdouble
iyydouble
izzdouble
ixydouble
ixzdouble
iyzdouble

Inertial

Inertial

FieldTypeLabelDescription
massdoubleMass (kg)
center-of-massVec3Center of mass (m)
inertiaInertiaInertia tensor

Quaternion

Quaternion

FieldTypeLabelDescription
xdouble
ydouble
zdouble
wdouble

SE2Pose

SE2Pose

FieldTypeLabelDescription
positionVec2(m)
angledouble(rad)

SE2Velocity

SE2Velocity

FieldTypeLabelDescription
linearVec2(m/s)
angulardouble(rad/s)

SE3Pose

SE3Pose

FieldTypeLabelDescription
positionVec3(m)
quaternionQuaternion
eulerEulerAngleZYX

Vec2

Vec2

FieldTypeLabelDescription
xdouble
ydouble

Vec3

Vec3

FieldTypeLabelDescription
xdouble
ydouble
zdouble

Top

rb/api/gripper-command.proto

GripperInitializationRequest

GripperInitializationRequest

FieldTypeLabelDescription
request-headerRequestHeaderRequest header
namestring

GripperInitializationResponse

GripperInitializationResponse

FieldTypeLabelDescription
response-headerResponseHeaderResponse header

GripperMoveRequest

GripperMoveRequest

FieldTypeLabelDescription
request-headerRequestHeaderRequest header
namestring
positionint32
velocityint32
forceint32

GripperMoveResponse

GripperMoveResponse

FieldTypeLabelDescription
response-headerResponseHeaderResponse header

Top

rb/api/gripper-command-service.proto

GripperCommandService

GripperCommandService

Method NameRequest TypeResponse TypeDescription
GripperInitializationGripperInitializationRequestGripperInitializationResponse
GripperMoveGripperMoveRequestGripperMoveResponseJoint command

Top

rb/api/head-command.proto

HeadCommand

HeadCommand

HeadCommand-Feedback

HeadCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
joint-position-command-feedbackJointPositionCommand.Feedback

HeadCommand-Request

HeadCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
joint-position-commandJointPositionCommand.Request

Top

rb/api/header.proto

CommonError

CommonError

FieldTypeLabelDescription
codeCommonError.CodeError code
messagestringHuman-readable error message

RequestHeader

RequestHeader

Standard request header

FieldTypeLabelDescription
request-timestampgoogle.protobuf.TimestampClient local system clock

ResponseHeader

ResponseHeader

Standard response header

FieldTypeLabelDescription
request-headerRequestHeaderEcho
request-received-timestampgoogle.protobuf.TimestampRobot clock
response-timestampgoogle.protobuf.TimestampRobot clock
errorCommonErrorIf set, there is error

CommonError-Code

CommonError.Code

NameNumberDescription
CODE-UNSPECIFIED0Code is not specified.
CODE-OK1Not an error. Request was successful.
CODE-INTERNAL-SERVER-ERROR2Service experienced an unexpected error state.
CODE-INVALID-REQUEST3Ill-formed request. Request arguments were not valid.

Top

rb/api/log.proto

GetLastLogRequest

GetLastLogRequest

FieldTypeLabelDescription
request-headerRequestHeader
log-countint32

GetLastLogResponse

GetLastLogResponse

FieldTypeLabelDescription
response-headerResponseHeader
logsLogrepeated

GetLogStreamRequest

GetLogStreamRequest

FieldTypeLabelDescription
request-headerRequestHeader
update-ratedoubleHz

GetLogStreamResponse

GetLogStreamResponse

FieldTypeLabelDescription
response-headerResponseHeader
logsLogrepeated

Log

Log

FieldTypeLabelDescription
timestampgoogle.protobuf.Timestamp
robot-system-timestampgoogle.protobuf.Timestamp
levelLog.Level
messagestring

SetLogLevelRequest

SetLogLevelRequest

FieldTypeLabelDescription
request-headerRequestHeader
levelLog.Level

SetLogLevelResponse

SetLogLevelResponse

FieldTypeLabelDescription
response-headerResponseHeader

Log-Level

Log.Level

NameNumberDescription
LEVEL-TRACE0
LEVEL-DEBUG1
LEVEL-INFO2
LEVEL-WARN3
LEVEL-ERROR4
LEVEL-CRITICAL5

Top

rb/api/log-service.proto

LogService

LogService

Method NameRequest TypeResponse TypeDescription
GetLastLogGetLastLogRequestGetLastLogResponse
GetLogStreamGetLogStreamRequestGetLogStreamResponse stream
SetLogLevelSetLogLevelRequestSetLogLevelResponse

Top

rb/api/mobility-command.proto

MobilityCommand

MobilityCommand

MobilityCommand-Feedback

MobilityCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
joint-velocity-command-feedbackJointVelocityCommand.Feedback
se2-velocity-command-feedbackSE2VelocityCommand.Feedback

MobilityCommand-Request

MobilityCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
joint-velocity-commandJointVelocityCommand.Request
se2-velocity-commandSE2VelocityCommand.Request

Top

rb/api/parameter.proto

GetParameterListRequest

GetParameterListRequest

FieldTypeLabelDescription
request-headerRequestHeader

GetParameterListResponse

GetParameterListResponse

FieldTypeLabelDescription
response-headerResponseHeader
parametersGetParameterListResponse.ParameterTyperepeated

GetParameterListResponse-ParameterType

GetParameterListResponse.ParameterType

FieldTypeLabelDescription
namestring
typeint32Type of parameter 0: int 1: double 2: std::string 3: std::array<double, 3> 4: std::array<double, 6> 5: std::array<double, 7>

GetParameterRequest

GetParameterRequest

FieldTypeLabelDescription
request-headerRequestHeader
namestring

GetParameterResponse

GetParameterResponse

FieldTypeLabelDescription
response-headerResponseHeader
parameterstring

ResetAllParametersToDefaultRequest

ResetAllParametersToDefaultRequest

FieldTypeLabelDescription
request-headerRequestHeader

ResetAllParametersToDefaultResponse

ResetAllParametersToDefaultResponse

FieldTypeLabelDescription
response-headerResponseHeader

ResetParameterToDefaultRequest

ResetParameterToDefaultRequest

FieldTypeLabelDescription
request-headerRequestHeader
namestring

ResetParameterToDefaultResponse

ResetParameterToDefaultResponse

FieldTypeLabelDescription
response-headerResponseHeader

SetParameterRequest

SetParameterRequest

FieldTypeLabelDescription
request-headerRequestHeader
namestring
parameterstring

SetParameterResponse

SetParameterResponse

FieldTypeLabelDescription
response-headerResponseHeader

Top

rb/api/parameter-service.proto

ParameterService

ParameterService

Method NameRequest TypeResponse TypeDescription
ResetAllParametersToDefaultResetAllParametersToDefaultRequestResetAllParametersToDefaultResponse
ResetParameterToDefaultResetParameterToDefaultRequestResetParameterToDefaultResponse
GetParameterGetParameterRequestGetParameterResponse
SetParameterSetParameterRequestSetParameterResponse
GetParameterListGetParameterListRequestGetParameterListResponse

Top

rb/api/ping.proto

PingRequest

PingRequest

FieldTypeLabelDescription
request-headerRequestHeader

PingResponse

PingResponse

FieldTypeLabelDescription
response-headerResponseHeader

Top

rb/api/ping-service.proto

PingService

PingService

Method NameRequest TypeResponse TypeDescription
PingPingRequestPingResponse

Top

rb/api/power.proto

JointCommandRequest

JointCommandRequest

FieldTypeLabelDescription
request-headerRequestHeaderRequest header
namestringMotor ID
commandJointCommandRequest.Command

JointCommandResponse

JointCommandResponse

FieldTypeLabelDescription
response-headerResponseHeaderResponse header
statusJointCommandResponse.Status
messagestringHuman-readable message for status

PowerCommandRequest

PowerCommandRequest

FieldTypeLabelDescription
request-headerRequestHeaderRequest header
namestringPower ID
commandPowerCommandRequest.Command

PowerCommandResponse

PowerCommandResponse

FieldTypeLabelDescription
response-headerResponseHeaderResponse header
statusPowerCommandResponse.Status
messagestringHuman-readable message for status

ToolFlangePowerCommandRequest

ToolFlangePowerCommandRequest

FieldTypeLabelDescription
request-headerRequestHeaderRequest header
namestringTool Flange name
commandToolFlangePowerCommandRequest.Command

ToolFlangePowerCommandResponse

ToolFlangePowerCommandResponse

FieldTypeLabelDescription
response-headerResponseHeaderResponse header

JointCommandRequest-Command

JointCommandRequest.Command

Modes for joint/motor command

NameNumberDescription
COMMAND-UNKNOWN0
COMMAND-SERVO-ON1
COMMAND-BRAKE-ENGAGE2
COMMAND-BRAKE-RELEASE3
COMMAND-HOME-OFFSET-RST4

JointCommandResponse-Status

JointCommandResponse.Status

NameNumberDescription
STATUS-UNKNOWN0
STATUS-SUCCESS1
STATUS-INTERNAL-ERROR2

PowerCommandRequest-Command

PowerCommandRequest.Command

Power command

NameNumberDescription
COMMAND-UNKNOWN0
COMMAND-POWER-ON1
COMMAND-POWER-OFF2

PowerCommandResponse-Status

PowerCommandResponse.Status

NameNumberDescription
STATUS-UNKNOWN0
STATUS-SUCCESS1
STATUS-INTERNAL-ERROR2

ToolFlangePowerCommandRequest-Command

ToolFlangePowerCommandRequest.Command

NameNumberDescription
COMMAND-UNKNOWN0
COMMAND-POWER-OFF1
COMMAND-POWER-12V2
COMMAND-POWER-24V3

Top

rb/api/power-service.proto

PowerService

PowerService

Method NameRequest TypeResponse TypeDescription
PowerCommandPowerCommandRequestPowerCommandResponseControl power of the robot
JointCommandJointCommandRequestJointCommandResponseJoint command
ToolFlangePowerCommandToolFlangePowerCommandRequestToolFlangePowerCommandResponseTool Flange

Top

rb/api/robot-command.proto

RobotCommand

RobotCommand

RobotCommand-Feedback

RobotCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
whole-body-command-feedbackWholeBodyCommand.Feedback
component-based-command-feedbackComponentBasedCommand.Feedback
jog-command-feedbackJogCommand.Feedback
statusRobotCommand.Feedback.Status
finish-codeRobotCommand.Feedback.FinishCode

RobotCommand-Request

RobotCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
whole-body-commandWholeBodyCommand.Request
component-based-commandComponentBasedCommand.Request
jog-commandJogCommand.Request

RobotCommandRequest

RobotCommandRequest

FieldTypeLabelDescription
request-headerRequestHeader
robot-commandRobotCommand.Request
priorityint32

RobotCommandResponse

RobotCommandResponse

FieldTypeLabelDescription
response-headerResponseHeader
feedbackRobotCommand.Feedback

RobotCommand-Feedback-FinishCode

RobotCommand.Feedback.FinishCode

NameNumberDescription
FINISH-CODE-UNKNOWN0
FINISH-CODE-OK1
FINISH-CODE-CANCELED2
FINISH-CODE-PREEMPTED3
FINISH-CODE-INITIALIZED-FAILED4
FINISH-CODE-CONTROL-MANAGER-IDLE5
FINISH-CODE-CONTROL-MANAGER-FAULT6
FINISH-CODE-UNEXPECTED-STATE7

RobotCommand-Feedback-Status

RobotCommand.Feedback.Status

NameNumberDescription
STATUS-IDLE0
STATUS-INITIALIZING1
STATUS-RUNNING2
STATUS-FINISHED3

Top

rb/api/robot-command-service.proto

RobotCommandService

RobotCommandService

Method NameRequest TypeResponse TypeDescription
RobotCommandRobotCommandRequestRobotCommandResponseIn case of sending and receiving a single command
RobotCommandStreamRobotCommandRequest streamRobotCommandResponse streamIn case of sending and receiving commands continuously

Top

rb/api/robot-info.proto

BatteryInfo

BatteryInfo

EMOInfo

EMOInfo

FieldTypeLabelDescription
namestring

GetRobotInfoRequest

GetRobotInfoRequest

FieldTypeLabelDescription
request-headerRequestHeader

GetRobotInfoResponse

GetRobotInfoResponse

FieldTypeLabelDescription
response-headerResponseHeader
robot-infoRobotInfo

GetRobotModelRequest

GetRobotModelRequest

FieldTypeLabelDescription
request-headerRequestHeader

GetRobotModelResponse

GetRobotModelResponse

FieldTypeLabelDescription
response-headerResponseHeader
modelstring

ImportRobotModelRequest

ImportRobotModelRequest

FieldTypeLabelDescription
request-headerRequestHeader
namestring
modelstring

ImportRobotModelResponse

ImportRobotModelResponse

FieldTypeLabelDescription
response-headerResponseHeader

JointInfo

JointInfo

FieldTypeLabelDescription
namestring
has-brakebool

PowerInfo

PowerInfo

FieldTypeLabelDescription
namestring

RobotInfo

RobotInfo

FieldTypeLabelDescription
robot-versionstring
sdk-commit-idstring
battery-infoBatteryInfo
power-infosPowerInforepeated
emo-infosEMOInforepeated
degree-of-freedomint32
joint-infosJointInforepeated
mobility-joint-idxuint32repeated
body-joint-idxuint32repeated
head-joint-idxuint32repeated

Top

rb/api/robot-info-service.proto

RobotInfoService

RobotInfoService

Method NameRequest TypeResponse TypeDescription
GetRobotInfoGetRobotInfoRequestGetRobotInfoResponse
GetRobotModelGetRobotModelRequestGetRobotModelResponse
ImportRobotModelImportRobotModelRequestImportRobotModelResponse

Top

rb/api/robot-state.proto

BatteryState

BatteryState

FieldTypeLabelDescription
voltagedoubleV
currentdoubleAmp
level-percentdouble%

Collision

Collision

FieldTypeLabelDescription
link1string
link2string
position1Vec3
position2Vec3
distancedouble

EMOState

EMOState

FieldTypeLabelDescription
stateEMOState.State

FTSensorData

FTSensorData

FieldTypeLabelDescription
time-since-last-updategoogle.protobuf.Duration
forceVec3
torqueVec3

GetControlManagerStateRequest

GetControlManagerStateRequest

FieldTypeLabelDescription
request-headerRequestHeader

GetControlManagerStateResponse

GetControlManagerStateResponse

FieldTypeLabelDescription
response-headerResponseHeader
control-manager-stateControlManagerState

GetRobotStateRequest

GetRobotStateRequest

FieldTypeLabelDescription
request-headerRequestHeader

GetRobotStateResponse

GetRobotStateResponse

FieldTypeLabelDescription
response-headerResponseHeader
robot-stateRobotState
control-manager-stateControlManagerState

GetRobotStateStreamRequest

GetRobotStateStreamRequest

FieldTypeLabelDescription
request-headerRequestHeader
update-ratedoubleHz

GetRobotStateStreamResponse

GetRobotStateStreamResponse

FieldTypeLabelDescription
response-headerResponseHeader
robot-stateRobotState
control-manager-stateControlManagerState

JointState

JointState

FieldTypeLabelDescription
is-readybool
fet-stateJointState.FETState
run-stateJointState.RunState
init-stateJointState.InitializationState
motor-typeuint32MOTOR STATE
motor-stateuint64
time-since-last-updategoogle.protobuf.Duration
power-onbool
positiondouble
velocitydouble
currentdouble
torquedouble
target-positiondouble
target-velocitydouble
target-feedback-gainuint32
target-feedforward-torquedouble

PowerState

PowerState

FieldTypeLabelDescription
statePowerState.State
voltagedouble

ResetOdometryRequest

ResetOdometryRequest

FieldTypeLabelDescription
request-headerRequestHeader
initial-poseSE2Pose

ResetOdometryResponse

ResetOdometryResponse

FieldTypeLabelDescription
response-headerResponseHeader

RobotState

RobotState

FieldTypeLabelDescription
timestampgoogle.protobuf.Timestamp
system-statSystemStatSystem Statistic
battery-stateBatteryStateBattery State
power-statesPowerStaterepeatedPower State
emo-statesEMOStaterepeatedEMO state
joint-statesJointStaterepeatedJoint State
tool-flange-rightToolFlangeStateTool Flange State
tool-flange-leftToolFlangeState
ft-sensor-rightFTSensorDataForce Torque Sensor
ft-sensor-leftFTSensorData
is-readydoublerepeated
positiondoublerepeated
velocitydoublerepeated
currentdoublerepeated
torquedoublerepeated
target-positiondoublerepeated
target-velocitydoublerepeated
target-feedback-gainuint32repeated
target-feedforward-torquedoublerepeated
odometrySE2PoseMobility State
center-of-massVec3Center Of Mass(Position of center of mass with respect t base link)
collisionsCollisionrepeatedCollisions

SystemStat

SystemStat

FieldTypeLabelDescription
cpu-usagedouble%
memory-usagedouble%
uptimedoublesec
program-uptimedoublesec

ToolFlangeState

ToolFlangeState

FieldTypeLabelDescription
time-since-last-updategoogle.protobuf.Duration
gyroVec3
accelerationVec3
switch-Abool
output-voltageint32

EMOState-State

EMOState.State

NameNumberDescription
STATE-RELEASED0
STATE-PRESSED1

JointState-FETState

JointState.FETState

NameNumberDescription
FET-STATE-UNKNOWN0
FET-STATE-ON1
FET-STATE-OFF2

JointState-InitializationState

JointState.InitializationState

NameNumberDescription
INIT-STATE-UNKNOWN0
INIT-STATE-INITIALIZED1
INIT-STATE-UNINITIALIZED2

JointState-RunState

JointState.RunState

NameNumberDescription
RUN-STATE-UNKNOWN0
RUN-STATE-CONTROL-ON1
RUN-STATE-CONTROL-OFF2

PowerState-State

PowerState.State

NameNumberDescription
STATE-UNKNOWN0
STATE-POWER-ON1
STATE-POWER-OFF2

Top

rb/api/robot-state-service.proto

RobotStateService

RobotStateService

Method NameRequest TypeResponse TypeDescription
GetRobotStateGetRobotStateRequestGetRobotStateResponse
GetRobotStateStreamGetRobotStateStreamRequestGetRobotStateStreamResponse stream
GetControlManagerStateGetControlManagerStateRequestGetControlManagerStateResponse
ResetOdometryResetOdometryRequestResetOdometryResponse

Top

rb/api/torso-command.proto

TorsoCommand

TorsoCommand

TorsoCommand-Feedback

TorsoCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
joint-position-command-feedbackJointPositionCommand.Feedback
gravity-compensation-command-feedbackGravityCompensationCommand.Feedback
cartesian-command-feedbackCartesianCommand.Feedback
impedance-control-command-feedbackImpedanceControlCommand.Feedback
optimal-control-command-feedbackOptimalControlCommand.Feedback

TorsoCommand-Request

TorsoCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
joint-position-commandJointPositionCommand.Request
gravity-compensation-commandGravityCompensationCommand.Request
cartesian-commandCartesianCommand.Request
impedance-control-commandImpedanceControlCommand.Request
optimal-control-commandOptimalControlCommand.Request

Top

rb/api/whole-body-command.proto

WholeBodyCommand

WholeBodyCommand

WholeBodyCommand-Feedback

WholeBodyCommand.Feedback

FieldTypeLabelDescription
command-header-feedbackCommandHeader.Feedback
stop-command-feedbackStopCommand.Feedback
real-time-control-command-feedbackRealTimeControlCommand.Feedback

WholeBodyCommand-Request

WholeBodyCommand.Request

FieldTypeLabelDescription
command-headerCommandHeader.Request
stop-commandStopCommand.Request
real-time-control-commandRealTimeControlCommand.Request

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)

rby1-sdk Released under the Apache License 2.0.