Skip to content

Protocol Documentation

Table of Contents

Top

rb/api/arm_command.proto

ArmCommand

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

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.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
tracking_errorsCartesianCommand.TrackingErrorrepeated

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

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

FieldTypeLabelDescription
position_errordouble
rotation_errordouble

GravityCompensationCommand

GravityCompensationCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback

GravityCompensationCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
onbool

ImpedanceControlCommand

ImpedanceControlCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
tracking_errorImpedanceControlCommand.TrackingError

ImpedanceControlCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
ref_link_namestring
link_namestring
TSE3Pose
translation_weightVec3
rotation_weightVec3

ImpedanceControlCommand.TrackingError

FieldTypeLabelDescription
position_errordouble
rotation_errordouble

JogCommand

JogCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
target_joint_namestring

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.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback

JointPositionCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
minimum_timegoogle.protobuf.Duration
positiondoublerepeated
velocity_limitdoublerepeated
acceleration_limitdoublerepeated
cutoff_frequencygoogle.protobuf.DoubleValue

JointVelocityCommand

JointVelocityCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback

JointVelocityCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
minimum_timegoogle.protobuf.Duration
velocitydoublerepeated
acceleration_limitdoublerepeated

OptimalControlCommand

OptimalControlCommand.CartesianCost

FieldTypeLabelDescription
ref_link_namestring
link_namestring
TSE3Pose
translation_weightdoubledefault = 1
rotation_weightdoubledefault = 1

OptimalControlCommand.CenterOfMassCost

FieldTypeLabelDescription
ref_link_namestring
poseVec3
weightdoubledefault = 1

OptimalControlCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
total_costdouble
cartesian_costsdoublerepeated
center_of_mass_costdouble
joint_position_costsdoublerepeated

OptimalControlCommand.JointPositionCost

FieldTypeLabelDescription
joint_namestring
target_positiondouble
weightdouble

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.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback

RealTimeControlCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
portuint32

SE2VelocityCommand

SE2VelocityCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback

SE2VelocityCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
minimum_timegoogle.protobuf.Duration
velocitySE2Velocity
acceleration_limitSE2Velocity

StopCommand

StopCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback

StopCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request

Top

rb/api/body_command.proto

BodyCommand

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

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.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
right_arm_command_feedbackArmCommand.Feedback
left_arm_command_feedbackArmCommand.Feedback
torso_command_feedbackTorsoCommand.Feedback

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.Feedback

FieldTypeLabelDescription
finishedbool

CommandHeader.Request

FieldTypeLabelDescription
control_hold_timegoogle.protobuf.Duration
gravityVec3
inertialsCommandHeader.Request.InertialsEntryrepeated

CommandHeader.Request.InertialsEntry

FieldTypeLabelDescription
keystring
valueInertial

Top

rb/api/component_based_command.proto

ComponentBasedCommand

ComponentBasedCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
mobility_command_feedbackMobilityCommand.Feedback
body_command_feedbackBodyCommand.Feedback
head_command_feedbackHeadCommand.Feedback

ComponentBasedCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
mobility_commandMobilityCommand.Request
body_commandBodyCommand.Request
head_commandHeadCommand.Request

Top

rb/api/control_manager.proto

ControlManagerCommandRequest

FieldTypeLabelDescription
request_headerRequestHeaderRequest header
commandControlManagerCommandRequest.Command
unlimited_mode_enabledgoogle.protobuf.BoolValue

ControlManagerCommandResponse

FieldTypeLabelDescription
response_headerResponseHeaderResponse header
control_manager_stateControlManagerState

ControlManagerState

FieldTypeLabelDescription
stateControlManagerState.State
time_scaledouble
control_stateControlManagerState.ControlState
enabled_joint_idxuint32repeated
unlimited_mode_enabledbool

GetTimeScaleRequest

FieldTypeLabelDescription
request_headerRequestHeaderRequest header

GetTimeScaleResponse

FieldTypeLabelDescription
response_headerResponseHeaderResponse header
time_scaledouble

SetTimeScaleRequest

FieldTypeLabelDescription
request_headerRequestHeaderRequest header
time_scaledouble

SetTimeScaleResponse

FieldTypeLabelDescription
response_headerResponseHeaderResponse header
current_time_scaledouble

ControlManagerCommandRequest.Command

Control manager command

NameNumberDescription
COMMAND_UNKNOWN0
COMMAND_ENABLE1
COMMAND_DISABLE2
COMMAND_RESET_FAULT3

ControlManagerState.ControlState

NameNumberDescription
CONTROL_STATE_UNKNOWN0
CONTROL_STATE_IDLE1
CONTROL_STATE_EXECUTING2
CONTROL_STATE_SWITCHING3

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

Method NameRequest TypeResponse TypeDescription
ControlManagerCommandControlManagerCommandRequestControlManagerCommandResponse
GetTimeScaleGetTimeScaleRequestGetTimeScaleResponse
SetTimeScaleSetTimeScaleRequestSetTimeScaleResponse

Top

rb/api/gamepad.proto

Gamepad

FieldTypeLabelDescription
buttonsboolrepeated
joystickdoublerepeated

UploadGamepadDataRequest

FieldTypeLabelDescription
request_headerRequestHeader
dataGamepad

UploadGamepadDataResponse

FieldTypeLabelDescription
response_headerResponseHeader

Top

rb/api/gamepad_service.proto

GamepadService

Method NameRequest TypeResponse TypeDescription
UploadGamepadDataGamepad streamUploadGamepadDataResponse

Top

rb/api/geometry.proto

EulerAngleZYX

FieldTypeLabelDescription
zdouble
ydouble
xdouble

Inertia

Inertia tensor components (kg*m^2)

FieldTypeLabelDescription
ixxdouble
iyydouble
izzdouble
ixydouble
ixzdouble
iyzdouble

Inertial

FieldTypeLabelDescription
massdoubleMass (kg)
center_of_massVec3Center of mass (m)
inertiaInertiaInertia tensor

Quaternion

FieldTypeLabelDescription
xdouble
ydouble
zdouble
wdouble

SE2Pose

FieldTypeLabelDescription
positionVec2(m)
angledouble(rad)

SE2Velocity

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

SE3Pose

FieldTypeLabelDescription
positionVec3(m)
quaternionQuaternion
eulerEulerAngleZYX

Vec2

FieldTypeLabelDescription
xdouble
ydouble

Vec3

FieldTypeLabelDescription
xdouble
ydouble
zdouble

Top

rb/api/gripper_command.proto

GripperInitializationRequest

FieldTypeLabelDescription
request_headerRequestHeaderRequest header
namestring

GripperInitializationResponse

FieldTypeLabelDescription
response_headerResponseHeaderResponse header

GripperMoveRequest

FieldTypeLabelDescription
request_headerRequestHeaderRequest header
namestring
positionint32
velocityint32
forceint32

GripperMoveResponse

FieldTypeLabelDescription
response_headerResponseHeaderResponse header

Top

rb/api/gripper_command_service.proto

GripperCommandService

Method NameRequest TypeResponse TypeDescription
GripperInitializationGripperInitializationRequestGripperInitializationResponse
GripperMoveGripperMoveRequestGripperMoveResponseJoint command

Top

rb/api/head_command.proto

HeadCommand

HeadCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
joint_position_command_feedbackJointPositionCommand.Feedback

HeadCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
joint_position_commandJointPositionCommand.Request

Top

rb/api/header.proto

CommonError

FieldTypeLabelDescription
codeCommonError.CodeError code
messagestringHuman-readable error message

RequestHeader

Standard request header

FieldTypeLabelDescription
request_timestampgoogle.protobuf.TimestampClient local system clock

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

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

FieldTypeLabelDescription
request_headerRequestHeader
log_countint32

GetLastLogResponse

FieldTypeLabelDescription
response_headerResponseHeader
logsLogrepeated

GetLogStreamRequest

FieldTypeLabelDescription
request_headerRequestHeader
update_ratedoubleHz

GetLogStreamResponse

FieldTypeLabelDescription
response_headerResponseHeader
logsLogrepeated

Log

FieldTypeLabelDescription
timestampgoogle.protobuf.Timestamp
robot_system_timestampgoogle.protobuf.Timestamp
levelLog.Level
messagestring

SetLogLevelRequest

FieldTypeLabelDescription
request_headerRequestHeader
levelLog.Level

SetLogLevelResponse

FieldTypeLabelDescription
response_headerResponseHeader

Log.Level

NameNumberDescription
LEVEL_TRACE0
LEVEL_DEBUG1
LEVEL_INFO2
LEVEL_WARN3
LEVEL_ERROR4
LEVEL_CRITICAL5

Top

rb/api/log_service.proto

LogService

Method NameRequest TypeResponse TypeDescription
GetLastLogGetLastLogRequestGetLastLogResponse
GetLogStreamGetLogStreamRequestGetLogStreamResponse stream
SetLogLevelSetLogLevelRequestSetLogLevelResponse

Top

rb/api/mobility_command.proto

MobilityCommand

MobilityCommand.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
joint_velocity_command_feedbackJointVelocityCommand.Feedback
se2_velocity_command_feedbackSE2VelocityCommand.Feedback

MobilityCommand.Request

FieldTypeLabelDescription
command_headerCommandHeader.Request
joint_velocity_commandJointVelocityCommand.Request
se2_velocity_commandSE2VelocityCommand.Request

Top

rb/api/parameter.proto

GetParameterListRequest

FieldTypeLabelDescription
request_headerRequestHeader

GetParameterListResponse

FieldTypeLabelDescription
response_headerResponseHeader
parametersGetParameterListResponse.ParameterTyperepeated

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

FieldTypeLabelDescription
request_headerRequestHeader
namestring

GetParameterResponse

FieldTypeLabelDescription
response_headerResponseHeader
parameterstring

ResetAllParametersToDefaultRequest

FieldTypeLabelDescription
request_headerRequestHeader

ResetAllParametersToDefaultResponse

FieldTypeLabelDescription
response_headerResponseHeader

ResetParameterToDefaultRequest

FieldTypeLabelDescription
request_headerRequestHeader
namestring

ResetParameterToDefaultResponse

FieldTypeLabelDescription
response_headerResponseHeader

SetParameterRequest

FieldTypeLabelDescription
request_headerRequestHeader
namestring
parameterstring

SetParameterResponse

FieldTypeLabelDescription
response_headerResponseHeader

Top

rb/api/parameter_service.proto

ParameterService

Method NameRequest TypeResponse TypeDescription
ResetAllParametersToDefaultResetAllParametersToDefaultRequestResetAllParametersToDefaultResponse
ResetParameterToDefaultResetParameterToDefaultRequestResetParameterToDefaultResponse
GetParameterGetParameterRequestGetParameterResponse
SetParameterSetParameterRequestSetParameterResponse
GetParameterListGetParameterListRequestGetParameterListResponse

Top

rb/api/ping.proto

PingRequest

FieldTypeLabelDescription
request_headerRequestHeader

PingResponse

FieldTypeLabelDescription
response_headerResponseHeader

Top

rb/api/ping_service.proto

PingService

Method NameRequest TypeResponse TypeDescription
PingPingRequestPingResponse

Top

rb/api/power.proto

JointCommandRequest

FieldTypeLabelDescription
request_headerRequestHeaderRequest header
namestringMotor ID
commandJointCommandRequest.Command

JointCommandResponse

FieldTypeLabelDescription
response_headerResponseHeaderResponse header
statusJointCommandResponse.Status
messagestringHuman-readable message for status

PowerCommandRequest

FieldTypeLabelDescription
request_headerRequestHeaderRequest header
namestringPower ID
commandPowerCommandRequest.Command

PowerCommandResponse

FieldTypeLabelDescription
response_headerResponseHeaderResponse header
statusPowerCommandResponse.Status
messagestringHuman-readable message for status

ToolFlangePowerCommandRequest

FieldTypeLabelDescription
request_headerRequestHeaderRequest header
namestringTool Flange name
commandToolFlangePowerCommandRequest.Command

ToolFlangePowerCommandResponse

FieldTypeLabelDescription
response_headerResponseHeaderResponse header

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

NameNumberDescription
STATUS_UNKNOWN0
STATUS_SUCCESS1
STATUS_INTERNAL_ERROR2

PowerCommandRequest.Command

Power command

NameNumberDescription
COMMAND_UNKNOWN0
COMMAND_POWER_ON1
COMMAND_POWER_OFF2

PowerCommandResponse.Status

NameNumberDescription
STATUS_UNKNOWN0
STATUS_SUCCESS1
STATUS_INTERNAL_ERROR2

ToolFlangePowerCommandRequest.Command

NameNumberDescription
COMMAND_UNKNOWN0
COMMAND_POWER_OFF1
COMMAND_POWER_12V2
COMMAND_POWER_24V3

Top

rb/api/power_service.proto

PowerService

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

Top

rb/api/robot_command.proto

RobotCommand

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

FieldTypeLabelDescription
command_headerCommandHeader.Request
whole_body_commandWholeBodyCommand.Request
component_based_commandComponentBasedCommand.Request
jog_commandJogCommand.Request

RobotCommandRequest

FieldTypeLabelDescription
request_headerRequestHeader
robot_commandRobotCommand.Request
priorityint32

RobotCommandResponse

FieldTypeLabelDescription
response_headerResponseHeader
feedbackRobotCommand.Feedback

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

NameNumberDescription
STATUS_IDLE0
STATUS_INITIALIZING1
STATUS_RUNNING2
STATUS_FINISHED3

Top

rb/api/robot_command_service.proto

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

EMOInfo

FieldTypeLabelDescription
namestring

GetRobotInfoRequest

FieldTypeLabelDescription
request_headerRequestHeader

GetRobotInfoResponse

FieldTypeLabelDescription
response_headerResponseHeader
robot_infoRobotInfo

GetRobotModelRequest

FieldTypeLabelDescription
request_headerRequestHeader

GetRobotModelResponse

FieldTypeLabelDescription
response_headerResponseHeader
modelstring

ImportRobotModelRequest

FieldTypeLabelDescription
request_headerRequestHeader
namestring
modelstring

ImportRobotModelResponse

FieldTypeLabelDescription
response_headerResponseHeader

JointInfo

FieldTypeLabelDescription
namestring
has_brakebool

PowerInfo

FieldTypeLabelDescription
namestring

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

Method NameRequest TypeResponse TypeDescription
GetRobotInfoGetRobotInfoRequestGetRobotInfoResponse
GetRobotModelGetRobotModelRequestGetRobotModelResponse
ImportRobotModelImportRobotModelRequestImportRobotModelResponse

Top

rb/api/robot_state.proto

BatteryState

FieldTypeLabelDescription
voltagedoubleV
currentdoubleAmp
level_percentdouble%

Collision

FieldTypeLabelDescription
link1string
link2string
position1Vec3
position2Vec3
distancedouble

EMOState

FieldTypeLabelDescription
stateEMOState.State

FTSensorData

FieldTypeLabelDescription
time_since_last_updategoogle.protobuf.Duration
forceVec3
torqueVec3

GetControlManagerStateRequest

FieldTypeLabelDescription
request_headerRequestHeader

GetControlManagerStateResponse

FieldTypeLabelDescription
response_headerResponseHeader
control_manager_stateControlManagerState

GetRobotStateRequest

FieldTypeLabelDescription
request_headerRequestHeader

GetRobotStateResponse

FieldTypeLabelDescription
response_headerResponseHeader
robot_stateRobotState
control_manager_stateControlManagerState

GetRobotStateStreamRequest

FieldTypeLabelDescription
request_headerRequestHeader
update_ratedoubleHz

GetRobotStateStreamResponse

FieldTypeLabelDescription
response_headerResponseHeader
robot_stateRobotState
control_manager_stateControlManagerState

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

FieldTypeLabelDescription
statePowerState.State
voltagedouble

ResetOdometryRequest

FieldTypeLabelDescription
request_headerRequestHeader
initial_poseSE2Pose

ResetOdometryResponse

FieldTypeLabelDescription
response_headerResponseHeader

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 | | collisions | Collision | repeated | Collisions |

SystemStat

FieldTypeLabelDescription
cpu_usagedouble%
memory_usagedouble%
uptimedoublesec
program_uptimedoublesec

ToolFlangeState

FieldTypeLabelDescription
time_since_last_updategoogle.protobuf.Duration
gyroVec3
accelerationVec3
switch_Abool
output_voltageint32

EMOState.State

NameNumberDescription
STATE_RELEASED0
STATE_PRESSED1

JointState.FETState

NameNumberDescription
FET_STATE_UNKNOWN0
FET_STATE_ON1
FET_STATE_OFF2

JointState.InitializationState

NameNumberDescription
INIT_STATE_UNKNOWN0
INIT_STATE_INITIALIZED1
INIT_STATE_UNINITIALIZED2

JointState.RunState

NameNumberDescription
RUN_STATE_UNKNOWN0
RUN_STATE_CONTROL_ON1
RUN_STATE_CONTROL_OFF2

PowerState.State

NameNumberDescription
STATE_UNKNOWN0
STATE_POWER_ON1
STATE_POWER_OFF2

Top

rb/api/robot_state_service.proto

RobotStateService

Method NameRequest TypeResponse TypeDescription
GetRobotStateGetRobotStateRequestGetRobotStateResponse
GetRobotStateStreamGetRobotStateStreamRequestGetRobotStateStreamResponse stream
GetControlManagerStateGetControlManagerStateRequestGetControlManagerStateResponse
ResetOdometryResetOdometryRequestResetOdometryResponse

Top

rb/api/torso_command.proto

TorsoCommand

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

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.Feedback

FieldTypeLabelDescription
command_header_feedbackCommandHeader.Feedback
stop_command_feedbackStopCommand.Feedback
real_time_control_command_feedbackRealTimeControlCommand.Feedback

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)