Protocol Documentation

Table of Contents

rb/api/arm_command.proto

Top

ArmCommand

ArmCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

joint_position_command_feedback JointPositionCommand.Feedback

gravity_compensation_command_feedback GravityCompensationCommand.Feedback

cartesian_command_feedback CartesianCommand.Feedback

impedance_control_command_feedback ImpedanceControlCommand.Feedback

ArmCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

joint_position_command JointPositionCommand.Request

gravity_compensation_command GravityCompensationCommand.Request

cartesian_command CartesianCommand.Request

impedance_control_command ImpedanceControlCommand.Request

rb/api/basic_command.proto

Top

CartesianCommand

CartesianCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

tracking_errors CartesianCommand.TrackingError repeated

CartesianCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

minimum_time google.protobuf.Duration

targets CartesianCommand.SE3PoseTarget repeated

stop_position_tracking_error google.protobuf.DoubleValue

stop_orientation_tracking_error google.protobuf.DoubleValue

CartesianCommand.SE3PoseTarget

FieldTypeLabelDescription
ref_link_name string

link_name string

T SE3Pose

linear_velocity_limit google.protobuf.DoubleValue

(m/s)

angular_velocity_limit google.protobuf.DoubleValue

(rad/s)

acceleration_limit_scaling google.protobuf.DoubleValue

default.linear_acceleration_limit * acceleration_limit_scaling default.angular_acceleration_limit * acceleration_limit_scaling (0, 1]

CartesianCommand.TrackingError

FieldTypeLabelDescription
position_error double

rotation_error double

GravityCompensationCommand

GravityCompensationCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

GravityCompensationCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

on bool

ImpedanceControlCommand

ImpedanceControlCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

tracking_error ImpedanceControlCommand.TrackingError

ImpedanceControlCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

ref_link_name string

link_name string

T SE3Pose

translation_weight Vec3

rotation_weight Vec3

ImpedanceControlCommand.TrackingError

FieldTypeLabelDescription
position_error double

rotation_error double

JogCommand

JogCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

target_joint_name string

JogCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

joint_name string

velocity_limit google.protobuf.DoubleValue

(rad/s) (optional)

acceleration_limit google.protobuf.DoubleValue

(rad/s^2) (optional)

absolute_position double

(rad)

relative_position double

(rad) current position + relative position

one_step bool

5 deg, true is positive move, false is negative move

JointPositionCommand

JointPositionCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

JointPositionCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

minimum_time google.protobuf.Duration

position double repeated

velocity_limit double repeated

acceleration_limit double repeated

cutoff_frequency google.protobuf.DoubleValue

JointVelocityCommand

JointVelocityCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

JointVelocityCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

minimum_time google.protobuf.Duration

velocity double repeated

acceleration_limit double repeated

OptimalControlCommand

OptimalControlCommand.CartesianCost

FieldTypeLabelDescription
ref_link_name string

link_name string

T SE3Pose

translation_weight double

default = 1

rotation_weight double

default = 1

OptimalControlCommand.CenterOfMassCost

FieldTypeLabelDescription
ref_link_name string

pose Vec3

weight double

default = 1

OptimalControlCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

total_cost double

cartesian_costs double repeated

center_of_mass_cost double

joint_position_costs double repeated

OptimalControlCommand.JointPositionCost

FieldTypeLabelDescription
joint_name string

target_position double

weight double

OptimalControlCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

cartesian_costs OptimalControlCommand.CartesianCost repeated

center_of_mass_cost OptimalControlCommand.CenterOfMassCost

joint_position_costs OptimalControlCommand.JointPositionCost repeated

velocity_limit_scaling google.protobuf.DoubleValue

qdot_limit * default.velocity_limit_scaling * velocity_limit_scaling default: 1.0 (0, 1]

velocity_tracking_gain google.protobuf.DoubleValue

default: default.optimal_control_command.velocity_tracking_gain (0, 1]

stop_cost google.protobuf.DoubleValue

default: default.optimal_control_command.stop_cost (0, \inf)

min_delta_cost google.protobuf.DoubleValue

(0, \inf)

patience google.protobuf.Int32Value

(0, \inf)

RealTimeControlCommand

RealTimeControlCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

RealTimeControlCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

port uint32

SE2VelocityCommand

SE2VelocityCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

SE2VelocityCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

minimum_time google.protobuf.Duration

velocity SE2Velocity

acceleration_limit SE2Velocity

StopCommand

StopCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

StopCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

rb/api/body_command.proto

Top

BodyCommand

BodyCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

joint_position_command_feedback JointPositionCommand.Feedback

optimal_control_command_feedback OptimalControlCommand.Feedback

gravity_compensation_command_feedback GravityCompensationCommand.Feedback

cartesian_command_feedback CartesianCommand.Feedback

body_component_based_command_feedback BodyComponentBasedCommand.Feedback

BodyCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

joint_position_command JointPositionCommand.Request

optimal_control_command OptimalControlCommand.Request

gravity_compensation_command GravityCompensationCommand.Request

cartesian_command CartesianCommand.Request

body_component_based_command BodyComponentBasedCommand.Request

rb/api/body_component_based_command.proto

Top

BodyComponentBasedCommand

BodyComponentBasedCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

right_arm_command_feedback ArmCommand.Feedback

left_arm_command_feedback ArmCommand.Feedback

torso_command_feedback TorsoCommand.Feedback

BodyComponentBasedCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

right_arm_command ArmCommand.Request

left_arm_command ArmCommand.Request

torso_command TorsoCommand.Request

rb/api/command_header.proto

Top

CommandHeader

CommandHeader.Feedback

FieldTypeLabelDescription
finished bool

CommandHeader.Request

FieldTypeLabelDescription
control_hold_time google.protobuf.Duration

gravity Vec3

inertials CommandHeader.Request.InertialsEntry repeated

CommandHeader.Request.InertialsEntry

FieldTypeLabelDescription
key string

value Inertial

rb/api/component_based_command.proto

Top

ComponentBasedCommand

ComponentBasedCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

mobility_command_feedback MobilityCommand.Feedback

body_command_feedback BodyCommand.Feedback

head_command_feedback HeadCommand.Feedback

ComponentBasedCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

mobility_command MobilityCommand.Request

body_command BodyCommand.Request

head_command HeadCommand.Request

rb/api/control_manager.proto

Top

ControlManagerCommandRequest

FieldTypeLabelDescription
request_header RequestHeader

Request header

command ControlManagerCommandRequest.Command

unlimited_mode_enabled google.protobuf.BoolValue

ControlManagerCommandResponse

FieldTypeLabelDescription
response_header ResponseHeader

Response header

control_manager_state ControlManagerState

ControlManagerState

FieldTypeLabelDescription
state ControlManagerState.State

time_scale double

control_state ControlManagerState.ControlState

enabled_joint_idx uint32 repeated

unlimited_mode_enabled bool

GetTimeScaleRequest

FieldTypeLabelDescription
request_header RequestHeader

Request header

GetTimeScaleResponse

FieldTypeLabelDescription
response_header ResponseHeader

Response header

time_scale double

SetTimeScaleRequest

FieldTypeLabelDescription
request_header RequestHeader

Request header

time_scale double

SetTimeScaleResponse

FieldTypeLabelDescription
response_header ResponseHeader

Response header

current_time_scale double

ControlManagerCommandRequest.Command

Control manager command

NameNumberDescription
COMMAND_UNKNOWN 0

COMMAND_ENABLE 1

COMMAND_DISABLE 2

COMMAND_RESET_FAULT 3

ControlManagerState.ControlState

NameNumberDescription
CONTROL_STATE_UNKNOWN 0

CONTROL_STATE_IDLE 1

CONTROL_STATE_EXECUTING 2

CONTROL_STATE_SWITCHING 3

ControlManagerState.State

NameNumberDescription
CONTROL_MANAGER_STATE_UNKNOWN 0

CONTROL_MANAGER_STATE_IDLE 1

CONTROL_MANAGER_STATE_ENABLED 2

CONTROL_MANAGER_STATE_MINOR_FAULT 3

CONTROL_MANAGER_STATE_MAJOR_FAULT 4

rb/api/control_manager_service.proto

Top

ControlManagerService

Method NameRequest TypeResponse TypeDescription
ControlManagerCommand ControlManagerCommandRequest ControlManagerCommandResponse

GetTimeScale GetTimeScaleRequest GetTimeScaleResponse

SetTimeScale SetTimeScaleRequest SetTimeScaleResponse

rb/api/gamepad.proto

Top

Gamepad

FieldTypeLabelDescription
buttons bool repeated

joystick double repeated

UploadGamepadDataRequest

FieldTypeLabelDescription
request_header RequestHeader

data Gamepad

UploadGamepadDataResponse

FieldTypeLabelDescription
response_header ResponseHeader

rb/api/gamepad_service.proto

Top

GamepadService

Method NameRequest TypeResponse TypeDescription
UploadGamepadData Gamepad stream UploadGamepadDataResponse

rb/api/geometry.proto

Top

EulerAngleZYX

FieldTypeLabelDescription
z double

y double

x double

Inertia

Inertia tensor components (kg*m^2)

FieldTypeLabelDescription
ixx double

iyy double

izz double

ixy double

ixz double

iyz double

Inertial

FieldTypeLabelDescription
mass double

Mass (kg)

center_of_mass Vec3

Center of mass (m)

inertia Inertia

Inertia tensor

Quaternion

FieldTypeLabelDescription
x double

y double

z double

w double

SE2Pose

FieldTypeLabelDescription
position Vec2

(m)

angle double

(rad)

SE2Velocity

FieldTypeLabelDescription
linear Vec2

(m/s)

angular double

(rad/s)

SE3Pose

FieldTypeLabelDescription
position Vec3

(m)

quaternion Quaternion

euler EulerAngleZYX

Vec2

FieldTypeLabelDescription
x double

y double

Vec3

FieldTypeLabelDescription
x double

y double

z double

rb/api/gripper_command.proto

Top

GripperInitializationRequest

FieldTypeLabelDescription
request_header RequestHeader

Request header

name string

GripperInitializationResponse

FieldTypeLabelDescription
response_header ResponseHeader

Response header

GripperMoveRequest

FieldTypeLabelDescription
request_header RequestHeader

Request header

name string

position int32

velocity int32

force int32

GripperMoveResponse

FieldTypeLabelDescription
response_header ResponseHeader

Response header

rb/api/gripper_command_service.proto

Top

GripperCommandService

Method NameRequest TypeResponse TypeDescription
GripperInitialization GripperInitializationRequest GripperInitializationResponse

GripperMove GripperMoveRequest GripperMoveResponse

Joint command

rb/api/head_command.proto

Top

HeadCommand

HeadCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

joint_position_command_feedback JointPositionCommand.Feedback

HeadCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

joint_position_command JointPositionCommand.Request

rb/api/header.proto

Top

CommonError

FieldTypeLabelDescription
code CommonError.Code

Error code

message string

Human-readable error message

RequestHeader

Standard request header

FieldTypeLabelDescription
request_timestamp google.protobuf.Timestamp

Client local system clock

ResponseHeader

Standard response header

FieldTypeLabelDescription
request_header RequestHeader

Echo

request_received_timestamp google.protobuf.Timestamp

Robot clock

response_timestamp google.protobuf.Timestamp

Robot clock

error CommonError

If set, there is error

CommonError.Code

NameNumberDescription
CODE_UNSPECIFIED 0

Code is not specified.

CODE_OK 1

Not an error. Request was successful.

CODE_INTERNAL_SERVER_ERROR 2

Service experienced an unexpected error state.

CODE_INVALID_REQUEST 3

Ill-formed request. Request arguments were not valid.

rb/api/log.proto

Top

GetLastLogRequest

FieldTypeLabelDescription
request_header RequestHeader

log_count int32

GetLastLogResponse

FieldTypeLabelDescription
response_header ResponseHeader

logs Log repeated

GetLogStreamRequest

FieldTypeLabelDescription
request_header RequestHeader

update_rate double

Hz

GetLogStreamResponse

FieldTypeLabelDescription
response_header ResponseHeader

logs Log repeated

Log

FieldTypeLabelDescription
timestamp google.protobuf.Timestamp

robot_system_timestamp google.protobuf.Timestamp

level Log.Level

message string

SetLogLevelRequest

FieldTypeLabelDescription
request_header RequestHeader

level Log.Level

SetLogLevelResponse

FieldTypeLabelDescription
response_header ResponseHeader

Log.Level

NameNumberDescription
LEVEL_TRACE 0

LEVEL_DEBUG 1

LEVEL_INFO 2

LEVEL_WARN 3

LEVEL_ERROR 4

LEVEL_CRITICAL 5

rb/api/log_service.proto

Top

LogService

Method NameRequest TypeResponse TypeDescription
GetLastLog GetLastLogRequest GetLastLogResponse

GetLogStream GetLogStreamRequest GetLogStreamResponse stream

SetLogLevel SetLogLevelRequest SetLogLevelResponse

rb/api/mobility_command.proto

Top

MobilityCommand

MobilityCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

joint_velocity_command_feedback JointVelocityCommand.Feedback

se2_velocity_command_feedback SE2VelocityCommand.Feedback

MobilityCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

joint_velocity_command JointVelocityCommand.Request

se2_velocity_command SE2VelocityCommand.Request

rb/api/parameter.proto

Top

GetParameterListRequest

FieldTypeLabelDescription
request_header RequestHeader

GetParameterListResponse

FieldTypeLabelDescription
response_header ResponseHeader

parameters GetParameterListResponse.ParameterType repeated

GetParameterListResponse.ParameterType

FieldTypeLabelDescription
name string

type int32

Type 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_header RequestHeader

name string

GetParameterResponse

FieldTypeLabelDescription
response_header ResponseHeader

parameter string

ResetAllParametersToDefaultRequest

FieldTypeLabelDescription
request_header RequestHeader

ResetAllParametersToDefaultResponse

FieldTypeLabelDescription
response_header ResponseHeader

ResetParameterToDefaultRequest

FieldTypeLabelDescription
request_header RequestHeader

name string

ResetParameterToDefaultResponse

FieldTypeLabelDescription
response_header ResponseHeader

SetParameterRequest

FieldTypeLabelDescription
request_header RequestHeader

name string

parameter string

SetParameterResponse

FieldTypeLabelDescription
response_header ResponseHeader

rb/api/parameter_service.proto

Top

ParameterService

Method NameRequest TypeResponse TypeDescription
ResetAllParametersToDefault ResetAllParametersToDefaultRequest ResetAllParametersToDefaultResponse

ResetParameterToDefault ResetParameterToDefaultRequest ResetParameterToDefaultResponse

GetParameter GetParameterRequest GetParameterResponse

SetParameter SetParameterRequest SetParameterResponse

GetParameterList GetParameterListRequest GetParameterListResponse

rb/api/ping.proto

Top

PingRequest

FieldTypeLabelDescription
request_header RequestHeader

PingResponse

FieldTypeLabelDescription
response_header ResponseHeader

rb/api/ping_service.proto

Top

PingService

Method NameRequest TypeResponse TypeDescription
Ping PingRequest PingResponse

rb/api/power.proto

Top

JointCommandRequest

FieldTypeLabelDescription
request_header RequestHeader

Request header

name string

Motor ID

command JointCommandRequest.Command

JointCommandResponse

FieldTypeLabelDescription
response_header ResponseHeader

Response header

status JointCommandResponse.Status

message string

Human-readable message for status

PowerCommandRequest

FieldTypeLabelDescription
request_header RequestHeader

Request header

name string

Power ID

command PowerCommandRequest.Command

PowerCommandResponse

FieldTypeLabelDescription
response_header ResponseHeader

Response header

status PowerCommandResponse.Status

message string

Human-readable message for status

ToolFlangePowerCommandRequest

FieldTypeLabelDescription
request_header RequestHeader

Request header

name string

Tool Flange name

command ToolFlangePowerCommandRequest.Command

ToolFlangePowerCommandResponse

FieldTypeLabelDescription
response_header ResponseHeader

Response header

JointCommandRequest.Command

Modes for joint/motor command

NameNumberDescription
COMMAND_UNKNOWN 0

COMMAND_SERVO_ON 1

COMMAND_BRAKE_ENGAGE 2

COMMAND_BRAKE_RELEASE 3

COMMAND_HOME_OFFSET_RST 4

JointCommandResponse.Status

NameNumberDescription
STATUS_UNKNOWN 0

STATUS_SUCCESS 1

STATUS_INTERNAL_ERROR 2

PowerCommandRequest.Command

Power command

NameNumberDescription
COMMAND_UNKNOWN 0

COMMAND_POWER_ON 1

COMMAND_POWER_OFF 2

PowerCommandResponse.Status

NameNumberDescription
STATUS_UNKNOWN 0

STATUS_SUCCESS 1

STATUS_INTERNAL_ERROR 2

ToolFlangePowerCommandRequest.Command

NameNumberDescription
COMMAND_UNKNOWN 0

COMMAND_POWER_OFF 1

COMMAND_POWER_12V 2

COMMAND_POWER_24V 3

rb/api/power_service.proto

Top

PowerService

Method NameRequest TypeResponse TypeDescription
PowerCommand PowerCommandRequest PowerCommandResponse

Control power of the robot

JointCommand JointCommandRequest JointCommandResponse

Joint command

ToolFlangePowerCommand ToolFlangePowerCommandRequest ToolFlangePowerCommandResponse

Tool Flange

rb/api/robot_command.proto

Top

RobotCommand

RobotCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

whole_body_command_feedback WholeBodyCommand.Feedback

component_based_command_feedback ComponentBasedCommand.Feedback

jog_command_feedback JogCommand.Feedback

status RobotCommand.Feedback.Status

finish_code RobotCommand.Feedback.FinishCode

RobotCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

whole_body_command WholeBodyCommand.Request

component_based_command ComponentBasedCommand.Request

jog_command JogCommand.Request

RobotCommandRequest

FieldTypeLabelDescription
request_header RequestHeader

robot_command RobotCommand.Request

priority int32

RobotCommandResponse

FieldTypeLabelDescription
response_header ResponseHeader

feedback RobotCommand.Feedback

RobotCommand.Feedback.FinishCode

NameNumberDescription
FINISH_CODE_UNKNOWN 0

FINISH_CODE_OK 1

FINISH_CODE_CANCELED 2

FINISH_CODE_PREEMPTED 3

FINISH_CODE_INITIALIZED_FAILED 4

FINISH_CODE_CONTROL_MANAGER_IDLE 5

FINISH_CODE_CONTROL_MANAGER_FAULT 6

FINISH_CODE_UNEXPECTED_STATE 7

RobotCommand.Feedback.Status

NameNumberDescription
STATUS_IDLE 0

STATUS_INITIALIZING 1

STATUS_RUNNING 2

STATUS_FINISHED 3

rb/api/robot_command_service.proto

Top

RobotCommandService

Method NameRequest TypeResponse TypeDescription
RobotCommand RobotCommandRequest RobotCommandResponse

단일 명령을 주고 받는 경우

RobotCommandStream RobotCommandRequest stream RobotCommandResponse stream

명령을 지속적으로 주고 받고자 하는 경우

rb/api/robot_info.proto

Top

BatteryInfo

EMOInfo

FieldTypeLabelDescription
name string

GetRobotInfoRequest

FieldTypeLabelDescription
request_header RequestHeader

GetRobotInfoResponse

FieldTypeLabelDescription
response_header ResponseHeader

robot_info RobotInfo

GetRobotModelRequest

FieldTypeLabelDescription
request_header RequestHeader

GetRobotModelResponse

FieldTypeLabelDescription
response_header ResponseHeader

model string

ImportRobotModelRequest

FieldTypeLabelDescription
request_header RequestHeader

name string

model string

ImportRobotModelResponse

FieldTypeLabelDescription
response_header ResponseHeader

JointInfo

FieldTypeLabelDescription
name string

has_brake bool

PowerInfo

FieldTypeLabelDescription
name string

RobotInfo

FieldTypeLabelDescription
robot_version string

sdk_commit_id string

battery_info BatteryInfo

power_infos PowerInfo repeated

emo_infos EMOInfo repeated

degree_of_freedom int32

joint_infos JointInfo repeated

mobility_joint_idx uint32 repeated

body_joint_idx uint32 repeated

head_joint_idx uint32 repeated

rb/api/robot_info_service.proto

Top

RobotInfoService

Method NameRequest TypeResponse TypeDescription
GetRobotInfo GetRobotInfoRequest GetRobotInfoResponse

GetRobotModel GetRobotModelRequest GetRobotModelResponse

ImportRobotModel ImportRobotModelRequest ImportRobotModelResponse

rb/api/robot_state.proto

Top

BatteryState

FieldTypeLabelDescription
voltage double

V

current double

Amp

level_percent double

%

EMOState

FieldTypeLabelDescription
state EMOState.State

FTSensorData

FieldTypeLabelDescription
time_since_last_update google.protobuf.Duration

force Vec3

torque Vec3

GetControlManagerStateRequest

FieldTypeLabelDescription
request_header RequestHeader

GetControlManagerStateResponse

FieldTypeLabelDescription
response_header ResponseHeader

control_manager_state ControlManagerState

GetRobotStateRequest

FieldTypeLabelDescription
request_header RequestHeader

GetRobotStateResponse

FieldTypeLabelDescription
response_header ResponseHeader

robot_state RobotState

control_manager_state ControlManagerState

GetRobotStateStreamRequest

FieldTypeLabelDescription
request_header RequestHeader

update_rate double

Hz

GetRobotStateStreamResponse

FieldTypeLabelDescription
response_header ResponseHeader

robot_state RobotState

control_manager_state ControlManagerState

JointState

FieldTypeLabelDescription
is_ready bool

fet_state JointState.FETState

run_state JointState.RunState

init_state JointState.InitializationState

motor_type uint32

MOTOR STATE

motor_state uint64

time_since_last_update google.protobuf.Duration

power_on bool

position double

velocity double

current double

torque double

target_position double

target_velocity double

target_feedback_gain uint32

target_feedforward_torque double

PowerState

FieldTypeLabelDescription
state PowerState.State

voltage double

ResetOdometryRequest

FieldTypeLabelDescription
request_header RequestHeader

initial_pose SE2Pose

ResetOdometryResponse

FieldTypeLabelDescription
response_header ResponseHeader

RobotState

FieldTypeLabelDescription
timestamp google.protobuf.Timestamp

system_stat SystemStat

System Statistic

battery_state BatteryState

Battery State

power_states PowerState repeated

Power State

emo_states EMOState repeated

EMO state

joint_states JointState repeated

Joint State

tool_flange_right ToolFlangeState

Tool Flange State

tool_flange_left ToolFlangeState

ft_sensor_right FTSensorData

Force Torque Sensor

ft_sensor_left FTSensorData

is_ready double repeated

position double repeated

velocity double repeated

current double repeated

torque double repeated

target_position double repeated

target_velocity double repeated

target_feedback_gain uint32 repeated

target_feedforward_torque double repeated

odometry SE2Pose

Mobility State

center_of_mass Vec3

Center Of Mass Position of center of mass with respect t base link

SystemStat

FieldTypeLabelDescription
cpu_usage double

%

memory_usage double

%

uptime double

sec

program_uptime double

sec

ToolFlangeState

FieldTypeLabelDescription
time_since_last_update google.protobuf.Duration

gyro Vec3

acceleration Vec3

switch_A bool

output_voltage int32

EMOState.State

NameNumberDescription
STATE_RELEASED 0

STATE_PRESSED 1

JointState.FETState

NameNumberDescription
FET_STATE_UNKNOWN 0

FET_STATE_ON 1

FET_STATE_OFF 2

JointState.InitializationState

NameNumberDescription
INIT_STATE_UNKNOWN 0

INIT_STATE_INITIALIZED 1

INIT_STATE_UNINITIALIZED 2

JointState.RunState

NameNumberDescription
RUN_STATE_UNKNOWN 0

RUN_STATE_CONTROL_ON 1

RUN_STATE_CONTROL_OFF 2

PowerState.State

NameNumberDescription
STATE_UNKNOWN 0

STATE_POWER_ON 1

STATE_POWER_OFF 2

rb/api/robot_state_service.proto

Top

RobotStateService

Method NameRequest TypeResponse TypeDescription
GetRobotState GetRobotStateRequest GetRobotStateResponse

GetRobotStateStream GetRobotStateStreamRequest GetRobotStateStreamResponse stream

GetControlManagerState GetControlManagerStateRequest GetControlManagerStateResponse

ResetOdometry ResetOdometryRequest ResetOdometryResponse

rb/api/torso_command.proto

Top

TorsoCommand

TorsoCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

joint_position_command_feedback JointPositionCommand.Feedback

gravity_compensation_command_feedback GravityCompensationCommand.Feedback

cartesian_command_feedback CartesianCommand.Feedback

impedance_control_command_feedback ImpedanceControlCommand.Feedback

optimal_control_command_feedback OptimalControlCommand.Feedback

TorsoCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

joint_position_command JointPositionCommand.Request

gravity_compensation_command GravityCompensationCommand.Request

cartesian_command CartesianCommand.Request

impedance_control_command ImpedanceControlCommand.Request

optimal_control_command OptimalControlCommand.Request

rb/api/whole_body_command.proto

Top

WholeBodyCommand

WholeBodyCommand.Feedback

FieldTypeLabelDescription
command_header_feedback CommandHeader.Feedback

stop_command_feedback StopCommand.Feedback

real_time_control_command_feedback RealTimeControlCommand.Feedback

WholeBodyCommand.Request

FieldTypeLabelDescription
command_header CommandHeader.Request

stop_command StopCommand.Request

real_time_control_command RealTimeControlCommand.Request

Scalar Value Types

.proto TypeNotesC++JavaPythonGoC#PHPRuby
double double double float float64 double float Float
float float float float float32 float float Float
int32 Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint32 instead. int32 int int int32 int integer Bignum or Fixnum (as required)
int64 Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint64 instead. int64 long int/long int64 long integer/string Bignum
uint32 Uses variable-length encoding. uint32 int int/long uint32 uint integer Bignum or Fixnum (as required)
uint64 Uses variable-length encoding. uint64 long int/long uint64 ulong integer/string Bignum or Fixnum (as required)
sint32 Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int32s. int32 int int int32 int integer Bignum or Fixnum (as required)
sint64 Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int64s. int64 long int/long int64 long integer/string Bignum
fixed32 Always four bytes. More efficient than uint32 if values are often greater than 2^28. uint32 int int uint32 uint integer Bignum or Fixnum (as required)
fixed64 Always eight bytes. More efficient than uint64 if values are often greater than 2^56. uint64 long int/long uint64 ulong integer/string Bignum
sfixed32 Always four bytes. int32 int int int32 int integer Bignum or Fixnum (as required)
sfixed64 Always eight bytes. int64 long int/long int64 long integer/string Bignum
bool bool boolean boolean bool bool boolean TrueClass/FalseClass
string A string must always contain UTF-8 encoded or 7-bit ASCII text. string String str/unicode string string string String (UTF-8)
bytes May contain any arbitrary sequence of bytes. string ByteString str []byte ByteString string String (ASCII-8BIT)