rby1_sdk.Robot_M#

class Robot_M#

Bases: pybind11_object

Robot (model: Model_M) control interface.

Provides high-level control interface for robot operations including connection management, power control, and command execution.

model#

Robot model configuration.

Type:

Model_M

__init__(*args, **kwargs)#

Methods

__init__(*args, **kwargs)

break_engage(self, dev_name)

Engage the brake for a device.

break_release(self, dev_name)

break_release(dev_name)

cancel_control(self)

Cancel current control operation.

connect(self[, max_retries, timeout_ms])

Attempts to establish a connection with the robot.

connect_wifi(self, ssid[, password, ...])

Connect to WiFi network.

control(self, control[, port, priority])

Start a blocking real-time control loop using a custom control callback.

create(address)

Create a robot instance.

create_command_stream(self[, priority])

Create a command stream for continuous command sending.

disable_control_manager(self)

Disable the control manager.

disconnect(self)

Disconnects from the robot.

disconnect_wifi(self)

Disconnect from WiFi network.

download_file(self, path, file_like)

Downloads a file from the robot and writes it into a file-like object.

enable_control_manager(self[, ...])

Enable the control manager.

factory_reset_all_parameters(self)

Factory reset all parameters to their default values.

factory_reset_parameter(self, name)

Factory reset a parameter to its default value.

get_control_manager_state(self)

Get control manager state.

get_dynamics(self[, urdf_model])

Get robot dynamics model.

get_fault_log_list(self)

Get fault log list.

get_head_position_pid_gains(self)

Get head position PID gains.

get_last_log(self, count)

Get last log entries.

get_left_arm_position_pid_gains(self)

Get left arm position PID gains.

get_parameter(self, name)

Retrieve a robot parameter.

get_parameter_list(self)

Get list of available parameters.

get_position_pid_gain(self, dev_name)

Get position PID gains for a device.

get_right_arm_position_pid_gains(self)

Get right arm position PID gains.

get_robot_info(self)

Retrieves static information about the robot, such as model name, SDK version, and joint configuration.

get_robot_model(self)

Get the current robot URDF model.

get_serial_device_list(self)

Get list of available serial devices on the robot.

get_state(self)

Get current robot state.

get_system_time(self)

Get robot system time.

get_time_scale(self)

Get the current time scale.

get_torso_position_pid_gains(self)

Get torso position PID gains.

get_wifi_status(self)

Get WiFi connection status.

has_established_time_sync(self)

Check if time synchronization is established.

home_offset_reset(self, dev_name)

Reset home offset for a device.

import_robot_model(self, name, model)

Import a robot model.

is_connected(self)

Checks whether the robot is currently connected.

is_power_on(self, dev_name)

Check if a device is powered on.

is_servo_on(self, dev_name)

Check if servo control is enabled for a device.

model()

Get the robot model configuration.

open_serial_stream(self, device_path, baudrate)

Open a serial stream.

power_off(self, dev_name)

Power off a device.

power_on(self, dev_name)

Power on a device.

reset_all_parameters(self)

Reset all parameters to their current values.

reset_all_parameters_to_default(self)

Reset all parameters to their default values (deprecated).

reset_battery_config(self)

Reset battery configuration to default.

reset_fault_control_manager(self)

Reset fault in the control manager.

reset_network_setting(self)

Reset network settings to default.

reset_odometry(self, angle, position)

reset_odometry(angle, position)

reset_parameter(self, name)

Reset a parameter to its current value.

reset_parameter_to_default(self, name)

Reset a parameter to its default value (deprecated).

scan_wifi(self)

Scan for available WiFi networks.

send_command(self, builder[, priority])

Send a command to the robot.

servo_off(self, dev_name)

Disable servo control for a device.

servo_on(self, dev_name)

Enable servo control for a device.

set_battery_config(self, cutoff_voltage, ...)

Set battery configuration.

set_battery_level(self, arg0)

Set battery level.

set_led_color(self, color[, duration, ...])

Set LED color.

set_parameter(self, name, value[, write_db])

Set a robot parameter.

set_position_d_gain(self, dev_name, d_gain)

Set position D gain for a device.

set_position_i_gain(self, dev_name, i_gain)

Set position I gain for a device.

set_position_p_gain(self, dev_name, p_gain)

Set position P gain for a device.

set_position_pid_gain(*args, **kwargs)

Overloaded function.

set_preset_position(self, joint_name)

Set preset position for a joint (only available for PVL-based motors).

set_system_time(*args, **kwargs)

Overloaded function.

set_time_scale(self, time_scale)

Set the time scale for motion execution.

set_tool_flange_digital_output(self, name, ...)

Set the digital output state of a specific channel on the tool flange of the specified arm.

set_tool_flange_digital_output_dual(self, ...)

Set the digital output states of two channels on the tool flange of the specified arm simultaneously.

set_tool_flange_output_voltage(self, name, ...)

Set tool flange output voltage.

start_log_stream(self, cb, rate)

Start log stream callback.

start_state_update(self, cb, rate)

Start state update callback.

start_time_sync(self, period_sec)

Start time synchronization.

stop_log_stream(self)

Stop log stream callback.

stop_state_update(self)

Stop state update callback.

stop_time_sync(self)

Stop time synchronization.

sync_time(self)

Synchronizes the timestamp of RobotState to UPC time instead of UTC.

wait_for_control_ready(self, timeout_ms)

Wait until the robot is ready to accept control commands.

break_engage(self: rby1_sdk.Robot_M, dev_name: str) bool#

Engage the brake for a device.

Parameters:

dev_name (str) – Device name (joint name) to engage brake. Supports regex patterns.

Examples

>>> # Engage brake for manitance
>>> robot.break_engage("right_arm_0")
break_release(self: rby1_sdk.Robot_M, dev_name: str) bool#

break_release(dev_name)

Release the brake for a device.

Parameters:

dev_name (str) – Device name (joint name) to release brake. Supports regex patterns.

Examples

>>> # Release brake to allow movement
>>> robot.break_release("right_arm_0")
cancel_control(self: rby1_sdk.Robot_M) bool#

Cancel current control operation.

connect(self: rby1_sdk.Robot_M, max_retries: int = 5, timeout_ms: int = 1000) bool#

Attempts to establish a connection with the robot.

Parameters:
  • max_retries (int, optional) – Maximum number of retries to connect. Default is 5.

  • timeout_ms (int, optional) – Timeout in milliseconds for each connection attempt. Default is 1000.

Returns:

True if the connection was successful, False otherwise.

Return type:

bool

Examples

>>> robot = rby1_sdk.create_robot("192.168.1.100", "a")
>>> if robot.connect():
...     print("Connected to robot")
... else:
...     print("Failed to connect")
>>> # Default: max_retries=5, timeout_ms=1000
>>> # Custom: robot.connect(max_retries=10, timeout_ms=2000)
connect_wifi(self: rby1_sdk.Robot_M, ssid: str, password: str = '', use_dhcp: bool = True, ip_address: str = '', gateway: str = '', dns: list[str] = []) bool#

Connect to WiFi network.

Parameters:
  • ssid (str) – WiFi network name.

  • password (str, optional) – WiFi password. Default is empty string.

  • use_dhcp (bool, optional) – Use DHCP. Default is True.

  • ip_address (str, optional) – Static IP address. Default is empty string.

  • gateway (str, optional) – Gateway address. Default is empty string.

  • dns (list[str], optional) – DNS servers. Default is empty string.

Examples

>>> # Connect using DHCP (automatic IP)
>>> robot.connect_wifi("MyWiFi", "mypassword123")
>>> # Connect with static IP configuration
>>> robot.connect_wifi("MyWiFi", "mypassword123", use_dhcp=False,
...                    ip_address="192.168.1.100/24", gateway="192.168.1.1")
>>> # Connect to open network
>>> robot.connect_wifi("OpenNetwork")
>>> # Check connection status
>>> status = robot.get_wifi_status()
>>> print(f"Connected: {status.connected}, SSID: {status.ssid}")
control(self: rby1_sdk.Robot_M, control: Callable[[rby1_sdk.Robot_M_ControlState], rby1_sdk.Robot_M_ControlInput], port: int = 0, priority: int = 1) bool#

Start a blocking real-time control loop using a custom control callback.

This function runs a UDP-based real-time loop that repeatedly calls the user-provided control(ControlState) -> ControlInput. The loop exits when the callback returns a ControlInput with finish=True, or when an error/abort occurs. The function returns True only if it finished via finish=True; otherwise False.

Parameters:
  • control (callable) – A callable that accepts a ControlState and returns a ControlInput. The callback is invoked for each received RT state packet.

  • port (int, optional) – UDP port to bind for the RT server. Use 0 to let the OS choose an available port (recommended). Default is 0.

  • priority (int, optional) – Command priority sent with the RT control request. Default is 1.

Returns:

True if the loop terminated because the callback set finish=True in ControlInput. False if the loop ended due to an error or abort (e.g., UDP bind failure, connection issue).

Return type:

bool

Notes

  • Blocking: This call blocks until the control loop ends. There is no handler for external cancellation. Design the callback to set finish=True when you want to stop.

  • GIL behavior: The function releases the Python GIL around I/O and reacquires it only when invoking your Python callback, allowing other Python threads to run between callbacks.

  • Performance: Keep the callback lightweight—avoid long computations or blocking I/O inside the callback to maintain RT responsiveness.

  • State fields: The provided ControlState includes timestamp t, and arrays such as position, velocity, current, and torque for all DoFs of the robot.

  • Errors: If the UDP server fails to bind (e.g., port unavailable), the function returns False immediately (and prints the error to stderr).

Examples

>>> import numpy as np
>>>
>>> # Stop after ~2 seconds using state.t
>>> t0 = {"t": None}
>>> def control_fn(state):
...     if t0["t"] is None:
...         t0["t"] = state.t
...     finish = (state.t - t0["t"]) >= 2.0
...     i = ControlInput()
...     i.mode.fill(rby.ControlMode.Position)
...     i.target = np.zeros_like(state.position)   # hold home
...     i.feedback_gain.fill(10)                   # simple P gain
...     i.feedforward_torque.fill(0)               # no torque feedforward
...     i.finish = finish
...     return i
>>> ok = robot.control(control_fn)
>>> print(ok)   # True if finished via finish=True
static create(address: str) rby1_sdk.Robot_M#

Create a robot instance.

Parameters:

address (str) – Robot network address, e.g. “192.168.1.100:50051”.

Returns:

Robot instance.

Return type:

Robot

Examples

>>> import rby1_sdk as rby
>>> robot = rby.Robot_A.create("192.168.30.1:50051")
>>> robot.connect()
>>> if robot.is_connected():
...     print("Robot connected successfully")
...     robot_info = robot.get_robot_info()
...     print(f"Robot model: {robot.model().model_name}")
...     # Note: Model A has mobile base (2-DOF) + torso (6-DOF) + right arm (7-DOF) + left arm (7-DOF) + head (2-DOF)
...     # Total joints: 2 + 6 + 7 + 7 + 2 = 24 DOF for model A
create_command_stream(self: rby1_sdk.Robot_M, priority: int = 1) rby1_sdk.Robot_M_CommandStreamHandler#

Create a command stream for continuous command sending.

Parameters:

priority (int, optional) – Command priority. Default is 1.

Returns:

Command stream handler.

Return type:

RobotCommandStreamHandler

Examples

>>> # Create command stream for continuous operation
>>> stream_handler = robot.create_command_stream(priority=1)
>>> # Send commands continuously
>>> for i in range(10):
...     command_builder = create_command(i)
...     stream_handler.send_command(command_builder, timeout_ms=1000)
...     time.sleep(1)
>>> # Through the handler, you can terminate control or check the current state
>>> stream_handler.cancel()
>>> # See examples/python/cartesian_command_stream.py for complete usage
disable_control_manager(self: rby1_sdk.Robot_M) bool#

Disable the control manager.

disconnect(self: rby1_sdk.Robot_M) None#

Disconnects from the robot.

disconnect_wifi(self: rby1_sdk.Robot_M) bool#

Disconnect from WiFi network.

download_file(self: rby1_sdk.Robot_M, path: str, file_like: object) bool#

Downloads a file from the robot and writes it into a file-like object.

Parameters:
  • path (str) – Relative path to the file on the robot’s file system. The base directory is defined by the RBY1_HOME environment variable (default: /root/.rby1).

  • file_like (file-like object) – Any object with a .write(bytes) method (e.g., io.BytesIO, a real file).

Returns:

True if the file was downloaded successfully.

Return type:

bool

Raises:

RuntimeError – If the gRPC call fails (e.g., network issue, file not found, internal error).

enable_control_manager(self: rby1_sdk.Robot_M, unlimited_mode_enabled: bool = False) bool#

Enable the control manager.

Parameters:

unlimited_mode_enabled (bool, optional) – Whether to enable unlimited mode. Default is False.

Examples

>>> # Enable control manager for robot control
>>> robot.enable_control_manager()
>>> # Enable with unlimited mode (use with caution)
>>> robot.enable_control_manager(unlimited_mode_enabled=True)
>>> # Must be called before sending commands
factory_reset_all_parameters(self: rby1_sdk.Robot_M) None#

Factory reset all parameters to their default values.

factory_reset_parameter(self: rby1_sdk.Robot_M, name: str) bool#

Factory reset a parameter to its default value.

Parameters:

name (str) – Parameter name.

get_control_manager_state(self: rby1_sdk.Robot_M) rby1_sdk.ControlManagerState#

Get control manager state.

Returns:

Current control manager state.

Return type:

ControlManagerState

Examples

>>> # Get control manager state
>>> ctrl_state = robot.get_control_manager_state()
>>> print(f"Control Manager state: {ctrl_state.state}")
>>> print(f"Control state: {ctrl_state.control_state}")
>>> # Check if control manager is enabled
>>> if ctrl_state.state == rby1_sdk.ControlManagerState.State.Enabled:
...     print("Control manager is enabled")
get_dynamics(self: rby1_sdk.Robot_M, urdf_model: str = '') rby1_sdk.dynamics.Robot_26#

Get robot dynamics model.

Parameters:

urdf_model (str, optional) – URDF model path. Default is empty string.

Returns:

Robot dynamics model.

Return type:

dyn.Robot

Examples

>>> # Get dynamics model with the model from connected robot
>>> dynamics_robot = robot.get_dynamics()
>>> # Get dynamics model with custom URDF
>>> dynamics_robot = robot.get_dynamics("/path/to/custom.urdf")
>>> # Useful for advanced control algorithms
get_fault_log_list(self: rby1_sdk.Robot_M) list[str]#

Get fault log list.

Returns:

List of fault log entries.

Return type:

list

get_head_position_pid_gains(self: rby1_sdk.Robot_M) list[rby1_sdk.PIDGain]#

Get head position PID gains.

Returns:

Head position PID gains.

Return type:

PIDGain

get_last_log(self: rby1_sdk.Robot_M, count: int) list[rby1_sdk.Log]#

Get last log entries.

Parameters:

count (int) – Number of log entries to retrieve.

Returns:

List of log entries.

Return type:

list

get_left_arm_position_pid_gains(self: rby1_sdk.Robot_M) list[rby1_sdk.PIDGain]#

Get left arm position PID gains.

Returns:

Left arm position PID gains.

Return type:

PIDGain

get_parameter(self: rby1_sdk.Robot_M, name: str) str#

Retrieve a robot parameter.

Parameters:

name (str) – Name of the parameter to retrieve.

Returns:

Parameter value. Returned as a JSON value: numeric values are returned as-is, strings are enclosed in quotes (”…”).

Return type:

any

Examples

>>> # Retrieve current parameter values
>>> acc_scaling = robot.get_parameter("default.acceleration_limit_scaling")
>>> cutoff_freq = robot.get_parameter("joint_position_command.cutoff_frequency")
>>> model_name = robot.get_parameter("robot_model_name")
>>> print(f"Acceleration scaling: {acc_scaling}")
>>> print(f"Cutoff frequency: {cutoff_freq}")
>>> print(f"Model name: {model_name}")
get_parameter_list(self: rby1_sdk.Robot_M) list[tuple[str, int]]#

Get list of available parameters.

Returns:

List of parameter names.

Return type:

list

Examples

>>> # Get all available parameters
>>> param_list = robot.get_parameter_list()
>>> print(f"Total parameters: {len(param_list)}")
>>> # List common parameter categories
>>> for param in param_list:
...     if param[0].startswith("default."):
...         print(f"Default param: {param}")
...     elif param[0].startswith("joint_position_command."):
...         print(f"Joint position param: {param}")
>>> # Common categories: default.*, joint_position_command.*, cartesian_command.*
get_position_pid_gain(self: rby1_sdk.Robot_M, dev_name: str) rby1_sdk.PIDGain#

Get position PID gains for a device.

Parameters:

dev_name (str) – Device name.

Returns:

Position PID gains for the device.

Return type:

PIDGain

Examples

>>> # Get PID gains for specific device
>>> torso_pid = robot.get_position_pid_gain("torso_5")
>>> print(f"Torso 5 P: {torso_pid.p_gain}, I: {torso_pid.i_gain}, D: {torso_pid.d_gain}")
>>> # Get PID gains for arm
>>> arm_pid = robot.get_position_pid_gain("right_arm_0")
>>> print(f"Right arm 0 P: {arm_pid.p_gain}")
>>> devices = ["torso_5", "right_arm_0", "left_arm_1", "head_0"]
>>> for device in devices:
...     pid = robot.get_position_pid_gain(device)
...     print(f"{device}: P={pid.p_gain}, I={pid.i_gain}, D={pid.d_gain}")
get_right_arm_position_pid_gains(self: rby1_sdk.Robot_M) list[rby1_sdk.PIDGain]#

Get right arm position PID gains.

Returns:

Right arm position PID gains.

Return type:

PIDGain

get_robot_info(self: rby1_sdk.Robot_M) rby1_sdk.RobotInfo#

Retrieves static information about the robot, such as model name, SDK version, and joint configuration.

Returns:

Structured metadata including joint details, device names, and robot model information.

Return type:

RobotInfo

Examples

>>> # Get robot information
>>> robot_info = robot.get_robot_info()
>>> print(f"SDK version: {robot_info.sdk_version}")
>>> print(f"Robot model name: {robot_info.robot_model_name}")
>>> print(f"Robot model version: {robot_info.robot_model_version}")
>>> print(f"Joint count: {len(robot_info.joint_infos)}")
>>> # Access joint information
>>> for joint in robot_info.joint_infos:
...     print(f"Joint: {joint.name}, Brake: {joint.has_brake}, Product name: {joint.product_name}, Firmware version: {joint.firmware_version}")
get_robot_model(self: rby1_sdk.Robot_M) str#

Get the current robot URDF model.

Returns:

Current robot model.

Return type:

RobotModel

get_serial_device_list(self: rby1_sdk.Robot_M) list[rby1_sdk.SerialDevice]#

Get list of available serial devices on the robot.

Returns:

List of available serial devices.

Return type:

list

Examples

>>> # Get available serial devices
>>> devices = robot.get_serial_device_list()
>>> print(f"Found {len(devices)} serial devices")
>>> # List device information
>>> for device in devices:
...     print(f"Path: {device.path}, Description: {device.description}")
>>> # Open serial stream to first device
>>> if devices:
...     stream = robot.open_serial_stream(devices[0].path, 115200)
>>> # Common device paths: /dev/ttyUSB0, /dev/ttyACM0, COM1, COM2
get_state(self: rby1_sdk.Robot_M) rby1_sdk.RobotState_M#

Get current robot state.

Returns:

Current robot state.

Return type:

RobotState

Examples

>>> robot_state = robot.get_state()
>>> model = robot.model()
>>> print(f"Joint positions: {robot_state.position}")
>>> print(f"Right arm position: {robot_state.position[model.right_arm_idx]}")
>>> # Note: Joint positions include mobile base (2-DOF) + torso (6-DOF) + right arm (7-DOF) + left arm (7-DOF) + head (2-DOF)
>>> # Total: 24 DOF for model A, 23 DOF for model M, 26 DOF for model M, 18 DOF for model UB
get_system_time(self: rby1_sdk.Robot_M) tuple[object, str]#

Get robot system time.

Returns:

(datetime, str): Robot system time and local time string.

Return type:

tuple

get_time_scale(self: rby1_sdk.Robot_M) float#

Get the current time scale.

Returns:

Current time scale value.

Return type:

float

Examples

>>> # Get current time scale
>>> current_scale = robot.get_time_scale()
>>> print(f"Current time scale: {current_scale}")
>>> # Check if robot is running at full speed
>>> if current_scale == 1.0:
...     print("Robot running at full speed")
>>> # Check if robot is slowed down
>>> elif current_scale < 1.0:
...     print(f"Robot running at {current_scale * 100}% speed")
get_torso_position_pid_gains(self: rby1_sdk.Robot_M) list[rby1_sdk.PIDGain]#

Get torso position PID gains.

Returns:

Torso position PID gains.

Return type:

PIDGain

Examples

>>> # Get current PID gains for torso
>>> torso_pid = robot.get_torso_position_pid_gains()[0]  # Get first (and only) torso device
>>> print(f"Torso P: {torso_pid.p_gain}, I: {torso_pid.i_gain}, D: {torso_pid.d_gain}")
>>> right_arm_pid = robot.get_right_arm_position_pid_gains()[0]
>>> print(f"Right arm: {right_arm_pid}")
get_wifi_status(self: rby1_sdk.Robot_M) rby1_sdk.WifiStatus | None#

Get WiFi connection status.

Returns:

Current WiFi status.

Return type:

WifiStatus

has_established_time_sync(self: rby1_sdk.Robot_M) bool#

Check if time synchronization is established.

Returns:

True if time sync is established, False otherwise.

Return type:

bool

home_offset_reset(self: rby1_sdk.Robot_M, dev_name: str) bool#

Reset home offset for a device.

Parameters:

dev_name (str) – Device name to reset home offset. Supports regex patterns.

import_robot_model(self: rby1_sdk.Robot_M, name: str, model: str) bool#

Import a robot model.

Parameters:
  • name (str) – Model name.

  • model (RobotModel) – Robot model to import.

is_connected(self: rby1_sdk.Robot_M) bool#

Checks whether the robot is currently connected.

Returns:

True if the robot is connected to the robot, False otherwise.

Return type:

bool

is_power_on(self: rby1_sdk.Robot_M, dev_name: str) bool#

Check if a device is powered on.

Parameters:

dev_name (str) – Device name to check. Supports regex patterns.

Returns:

True if device is powered on, False otherwise.

Return type:

bool

is_servo_on(self: rby1_sdk.Robot_M, dev_name: str) bool#

Check if servo control is enabled for a device.

Parameters:

dev_name (str) – Device name to check. Supports regex patterns.

Returns:

True if servo control is enabled, False otherwise.

Return type:

bool

static model() rby1_sdk.Model_M#

Get the robot model configuration.

Returns:

Robot model configuration object.

Return type:

Model_M

open_serial_stream(self: rby1_sdk.Robot_M, device_path: str, baudrate: int, bytesize: int = 8, parity: str = 'N', stopbits: int = 1) rby1_sdk.SerialStream#

Open a serial stream.

Parameters:
  • device_path (str) – Path to serial device.

  • baudrate (int) – Baud rate.

  • bytesize (int, optional) – Data bits. Default is 8.

  • parity (str, optional) – Parity setting. Default is ‘N’.

  • stopbits (int, optional) – Stop bits. Default is 1.

Returns:

Serial stream object.

Return type:

SerialStream

Examples

>>> # Open serial stream with default settings
>>> stream = robot.open_serial_stream("/dev/ttyUSB0", 115200)
>>> # Open with custom settings
>>> stream = robot.open_serial_stream("/dev/ttyUSB1", 9600, bytesize=7, parity='E', stopbits=2)
>>> # Common baudrates: 9600, 19200, 38400, 57600, 115200
>>> # Parity: 'N' (none), 'E' (even), 'O' (odd)
>>> # Stop bits: 1, 2
power_off(self: rby1_sdk.Robot_M, dev_name: str) bool#

Power off a device.

Parameters:

dev_name (str) – Device name to power off. Supports regex patterns.

power_on(self: rby1_sdk.Robot_M, dev_name: str) bool#

Power on a device.

Parameters:

dev_name (str) – Device name to power on. Supports regex patterns.

Examples

>>> robot.connect()
>>> if not robot.is_power_on(".*"):
...     robot.power_on(".*")
...     print("Robot powered on")
>>> # Pattern ".*" powers on all devices
>>> # Specific device: robot.power_on("12v"), robot.power_on("24v"), etc.
reset_all_parameters(self: rby1_sdk.Robot_M) None#

Reset all parameters to their current values.

reset_all_parameters_to_default(self: rby1_sdk.Robot_M) None#

Reset all parameters to their default values (deprecated).

Deprecated since version 0.6.0: Use factory_reset_all_parameters() instead.

Note

This method is deprecated. Use factory_reset_all_parameters() instead.

reset_battery_config(self: rby1_sdk.Robot_M) bool#

Reset battery configuration to default.

reset_fault_control_manager(self: rby1_sdk.Robot_M) bool#

Reset fault in the control manager.

reset_network_setting(self: rby1_sdk.Robot_M) bool#

Reset network settings to default.

reset_odometry(self: rby1_sdk.Robot_M, angle: float, position: numpy.ndarray[numpy.float64[2, 1]]) bool#

reset_odometry(angle, position)

Reset odometry to specified values.

Parameters:

Examples

>>> import numpy as np
>>> # Reset odometry to origin
>>> robot.reset_odometry(angle=0.0, position=np.array([0.0, 0.0]))
>>> # Reset to specific position and orientation
>>> robot.reset_odometry(angle=np.pi/2, position=np.array([1.0, 2.0]))
>>> # Useful for mobile base navigation
>>> # Position is [x, y] in meters, angle is yaw in rad
reset_parameter(self: rby1_sdk.Robot_M, name: str) bool#

Reset a parameter to its current value.

Parameters:

name (str) – Parameter name.

reset_parameter_to_default(self: rby1_sdk.Robot_M, name: str) bool#

Reset a parameter to its default value (deprecated).

Parameters:

Note

This method is deprecated. Use factory_reset_parameter() instead.

scan_wifi(self: rby1_sdk.Robot_M) list[rby1_sdk.WifiNetwork]#

Scan for available WiFi networks.

Returns:

List of available WiFi networks.

Return type:

list

Examples

>>> # Scan for available WiFi networks
>>> networks = robot.scan_wifi()
>>> print(f"Found {len(networks)} networks")
>>> # List network information
>>> for network in networks:
...     print(f"SSID: {network.ssid}, Signal: {network.signal_strength}")
>>> # Connect to a network
>>> if networks:
...     robot.connect_wifi(networks[0].ssid, "password")
send_command(self: rby1_sdk.Robot_M, builder: rby1_sdk.RobotCommandBuilder, priority: int = 1) rby1_sdk.Robot_M_CommandHandler#

Send a command to the robot.

Parameters:
  • builder (CommandBuilder) – Command builder to send.

  • priority (int, optional) – Command priority. Default is 1.

Returns:

Command handler for monitoring execution.

Return type:

RobotCommandHandler

Examples

>>> from rby1_sdk import RobotCommandBuilder, ComponentBasedCommandBuilder
>>> from rby1_sdk import BodyComponentBasedCommandBuilder, JointPositionCommandBuilder
>>> # Create command with method chaining (standard pattern)
>>> command = RobotCommandBuilder().set_command(
...     ComponentBasedCommandBuilder().set_body_command(
...         BodyComponentBasedCommandBuilder()
...             .set_torso_command(
...                 JointPositionCommandBuilder()
...                     .set_position([0, 0, 0, 0, 0, 0])  # 6-DOF torso
...                     .set_minimum_time(2.0)
...             )
...     )
... )
>>> handler = robot.send_command(command)
>>> handler.wait()  # Wait for completion
>>> # This pattern is used in most examples: examples/python/07_impedance_control.py, 09_demo_motion.py, etc.
servo_off(self: rby1_sdk.Robot_M, dev_name: str) bool#

Disable servo control for a device.

Parameters:

dev_name (str) – Device name to disable servo control. Supports regex patterns.

Examples

>>> # Disable servo control for safety
>>> robot.servo_off(".*")  # All motor drivers
>>> # Specific device: robot.servo_off("^torso_.*")
servo_on(self: rby1_sdk.Robot_M, dev_name: str) bool#

Enable servo control for a device.

Parameters:

dev_name (str) – Device name to enable servo control. Supports regex patterns.

Examples

>>> robot.connect()
>>> if not robot.is_servo_on(".*"):
...     robot.servo_on(".*")  # Servo on all devices
...     print("All devices servoed on")
>>> # Specific device: robot.servo_on("^torso_.*"), robot.servo_on("^right_arm_.*"), etc.
set_battery_config(self: rby1_sdk.Robot_M, cutoff_voltage: float, fully_charged_voltage: float, coefficients: Annotated[list[float], FixedSize(4)]) bool#

Set battery configuration.

set_battery_level(self: rby1_sdk.Robot_M, arg0: float) bool#

Set battery level.

Parameters:

level (float) – Battery level percentage (0.0 to 100.0).

Examples

>>> # Set battery level for testing
>>> robot.set_battery_level(100.0)  # Full battery
>>> robot.set_battery_level(50.0)   # Half battery
>>> robot.set_battery_level(25.0)   # Quarter battery
>>> robot.set_battery_level(0.0)    # Empty battery
>>> # Range: 0.0 to 100.0
>>> # Useful for using custom battery
set_led_color(self: rby1_sdk.Robot_M, color: rby1_sdk.Color, duration: float = 1, transition_time: float = 0, blinking: bool = False, blinking_freq: float = 1) bool#

Set LED color.

Parameters:
  • color (Color) – LED color.

  • duration (float, optional) – Duration in seconds. Default is 1.

  • transition_time (float, optional) – Transition time in seconds. Default is 0.

  • blinking (bool, optional) – Whether to blink. Default is False.

  • blinking_freq (float, optional) – Blinking frequency in Hz. Default is 1.

Examples

>>> from rby1_sdk import Color
>>> # Set LED to red for 5 seconds
>>> robot.set_led_color(Color(255, 0, 0), duration=5.0)
>>> # Set LED to green with 1 second transition
>>> robot.set_led_color(Color(0, 255, 0), transition_time=1.0)
>>> # Set LED to blue with blinking
>>> robot.set_led_color(Color(0, 0, 255), blinking=True, blinking_freq=2.0)
>>> # Set LED to white with custom duration and transition
>>> robot.set_led_color(Color(255, 255, 255), duration=10.0, transition_time=2.0)
set_parameter(self: rby1_sdk.Robot_M, name: str, value: str, write_db: bool = True) bool#

Set a robot parameter.

Parameters:
  • name (str) – Parameter name.

  • value (any) – Parameter value.

  • write_db (bool, optional) – Whether to write to database. Default is True.

Examples

>>> # Set acceleration limit scaling
>>> robot.set_parameter("default.acceleration_limit_scaling", "0.8")
>>> # Set joint position command cutoff frequency
>>> robot.set_parameter("joint_position_command.cutoff_frequency", "5")
>>> # Set hotspot SSID name
>>> robot.set_parameter("hotspot.ssid", "\"RBY1_HOTSPOT\"") # For str value, use escaped quotes
>>> # Set without writing to database (Return ``False`` if matching parameter not found)
>>> robot.set_parameter("temp.parameter", "value", write_db=False)
False
set_position_d_gain(self: rby1_sdk.Robot_M, dev_name: str, d_gain: int) bool#

Set position D gain for a device.

Parameters:
  • dev_name (str) – Device name.

  • d_gain (int) – D gain value.

Examples

>>> # Set D gain for specific devices
>>> robot.set_position_d_gain("torso_5", 400)
set_position_i_gain(self: rby1_sdk.Robot_M, dev_name: str, i_gain: int) bool#

Set position I gain for a device.

Parameters:
  • dev_name (str) – Device name.

  • i_gain (int) – I gain value.

Examples

>>> # Set I gain for specific devices
>>> robot.set_position_i_gain("torso_5", 40)
set_position_p_gain(self: rby1_sdk.Robot_M, dev_name: str, p_gain: int) bool#

Set position P gain for a device.

Parameters:
  • dev_name (str) – Device name.

  • p_gain (int) – P gain value.

Examples

>>> # Set P gain for specific devices
>>> robot.set_position_p_gain("torso_5", 220)
set_position_pid_gain(*args, **kwargs)#

Overloaded function.

  1. set_position_pid_gain(self: rby1_sdk.Robot_M, dev_name: str, p_gain: int, i_gain: int, d_gain: int) -> bool

Set position PID gains for a device.

Parameters:
  • dev_name (str) – Device name.

  • p_gain (int) – P gain value.

  • i_gain (int) – I gain value.

  • d_gain (int) – D gain value.

Returns:

True if successful, False otherwise.

Return type:

bool

Examples

>>> # Set all PID gains at once for a device
>>> robot.set_position_pid_gain("right_arm_0", 80, 15, 200)
>>> robot.set_position_pid_gain("right_arm_1", 80, 15, 200)
>>> robot.set_position_pid_gain("right_arm_2", 80, 15, 200)
>>> robot.set_position_pid_gain("right_arm_3", 35, 5, 80)
>>> robot.set_position_pid_gain("right_arm_4", 30, 5, 70)
>>> robot.set_position_pid_gain("right_arm_5", 30, 5, 70)
>>> robot.set_position_pid_gain("right_arm_6", 100, 5, 120)
  1. set_position_pid_gain(self: rby1_sdk.Robot_M, dev_name: str, pid_gain: rby1_sdk.PIDGain) -> bool

Set position PID gains for a device using PIDGain object.

Parameters:
  • dev_name (str) – Device name.

  • pid_gain (PIDGain) – PID gain object.

Returns:

True if successful, False otherwise.

Return type:

bool

set_preset_position(self: rby1_sdk.Robot_M, joint_name: str) bool#

Set preset position for a joint (only available for PVL-based motors).

Parameters:

joint_name (str) – Joint name to set preset position.

Examples

>>> # Set preset position for specific joints
>>> robot.set_preset_position("right_arm_6")  # Right arm joint 6
>>> # Preset position is used as reference for home offset
set_system_time(*args, **kwargs)#

Overloaded function.

  1. set_system_time(self: rby1_sdk.Robot_M, datetime: object) -> bool

Set robot system time.

Parameters:

datetime (datetime.datetime) – New system time.

  1. set_system_time(self: rby1_sdk.Robot_M, datetime: object, time_zone: str) -> bool

Set robot system time with timezone.

Parameters:
set_time_scale(self: rby1_sdk.Robot_M, time_scale: float) float#

Set the time scale for motion execution.

Parameters:

time_scale (float) – Time scale value (0.0 to 1.0).

Examples

>>> # Set time scale for motion execution
>>> robot.set_time_scale(1.0)   # Normal speed (100%)
>>> robot.set_time_scale(0.5)   # Half speed (50%)
>>> robot.set_time_scale(0.25)  # Quarter speed (25%)
>>> # Range: 0.0 (stopped) to 1.0 (full speed)
>>> # Useful for testing and safety
set_tool_flange_digital_output(self: rby1_sdk.Robot_M, name: str, channel: int, state: bool) bool#

Set the digital output state of a specific channel on the tool flange of the specified arm.

Parameters:
  • name (str) – Arm identifier. Must be either “right” or “left”, indicating the tool flange of the right or left arm.

  • channel (int) – Digital output channel index.

  • state (bool) – Desired state of the digital output (True = ON, False = OFF).

Returns:

True if the command was successfully sent, False otherwise.

Return type:

bool

Examples

>>> # Turn on channel 0 on the right arm tool flange
>>> robot.set_tool_flange_digital_output("right", 0, True)
set_tool_flange_digital_output_dual(self: rby1_sdk.Robot_M, name: str, state_0: bool, state_1: bool) bool#

Set the digital output states of two channels on the tool flange of the specified arm simultaneously.

Parameters:
  • name (str) – Arm identifier. Must be either “right” or “left”, indicating the tool flange of the right or left arm.

  • state_0 (bool) – Desired state for digital output channel 0 (True = ON, False = OFF).

  • state_1 (bool) – Desired state for digital output channel 1 (True = ON, False = OFF).

Returns:

True if the command was successfully sent, False otherwise.

Return type:

bool

Examples

>>> # Turn on channel 0 and turn off channel 1 on the left arm tool flange
>>> robot.set_tool_flange_digital_output_dual("left", True, False)
set_tool_flange_output_voltage(self: rby1_sdk.Robot_M, name: str, voltage: int) bool#

Set tool flange output voltage.

Parameters:
  • name (str) – Tool flange name “right” or “left”.

  • voltage (int) – Output voltage in volts.

Examples

>>> # Set tool flange output voltage
>>> robot.set_tool_flange_output_voltage("right", 12)  # 12V output
>>> robot.set_tool_flange_output_voltage("left", 24)  # 24V output
>>> # Common voltages: 12V, 24V
>>> # Use 0V to turn off output
>>> # Note: This method sets voltage for both tool flanges (right and left)
start_log_stream(self: rby1_sdk.Robot_M, cb: Callable[[list[rby1_sdk.Log]], None], rate: float) None#

Start log stream callback.

Parameters:
  • cb (callable) – Callback function for log updates.

  • rate (float) – Update rate in Hz.

Examples

>>> def log_callback(log_entries):
...     for log in log_entries:
...         print(f"{log.timestamp} - {log.level} - {log.message}")
>>> # Start log stream at 10 Hz
>>> robot.start_log_stream(log_callback, 10.0)
>>> # Stop when done: robot.stop_log_stream()
start_state_update(self: rby1_sdk.Robot_M, cb: Callable, rate: float) None#

Start state update callback.

Parameters:
  • cb (callable) – Callback function with 1 or 2 parameters: - cb(robot_state) or cb(robot_state, control_manager_state)

  • rate (float) – Update rate in Hz.

Examples

>>> def state_callback(robot_state):
...     print(f"Timestamp: {robot_state.timestamp}, Joint positions: {robot_state.position}")
>>> # Start state updates at 100 Hz
>>> robot.start_state_update(state_callback, 100.0)
>>> # Stop when done: robot.stop_state_update()
start_time_sync(self: rby1_sdk.Robot_M, period_sec: int) bool#

Start time synchronization.

Parameters:

period_sec (float) – Synchronization period in seconds.

stop_log_stream(self: rby1_sdk.Robot_M) None#

Stop log stream callback.

stop_state_update(self: rby1_sdk.Robot_M) None#

Stop state update callback.

stop_time_sync(self: rby1_sdk.Robot_M) bool#

Stop time synchronization.

sync_time(self: rby1_sdk.Robot_M) bool#

Synchronizes the timestamp of RobotState to UPC time instead of UTC. Useful when synchronizing multiple devices to UPC time.

wait_for_control_ready(self: rby1_sdk.Robot_M, timeout_ms: int) bool#

Wait until the robot is ready to accept control commands.

Parameters:

timeout_ms (int) – Timeout in milliseconds.

Returns:

True if the robot is ready to accept control (you can now set control). False if the timeout expired before the robot became ready.

Return type:

bool

Examples

>>> # Wait for control to be ready
>>> if robot.wait_for_control_ready(timeout_ms=5000):
...     print("Control is ready, you can now set control commands.")
... else:
...     print("Timeout: control is not ready.")
>>> # Call after servo_on() and before sending control commands