rby1_sdk.DynamixelBus#

class DynamixelBus#

Bases: pybind11_object

Dynamixel bus communication interface.

This class provides low-level communication with Dynamixel servos including motor control, PID tuning, and status monitoring.

ProtocolVersion#

Dynamixel protocol version (2.0).

Type:

float

DefaultBaudrate#

Default communication baudrate (2000000).

Type:

int

AddrTorqueEnable#

Memory address for torque enable/disable (64).

Type:

int

AddrPresentCurrent#

Memory address for current reading (126).

Type:

int

AddrPresentVelocity#

Memory address for velocity reading (128).

Type:

int

AddrPresentPosition#

Memory address for position reading (132).

Type:

int

AddrGoalCurrent#

Memory address for current goal setting (102).

Type:

int

AddrGoalPosition#

Memory address for position goal setting (104).

Type:

int

AddrOperatingMode#

Memory address for operating mode setting (11).

Type:

int

AddrPresentButtonState#

Memory address for button state reading (12).

Type:

int

AddrGoalVibrationLevel#

Memory address for vibration level setting (13).

Type:

int

AddrPositionPGain#

Memory address for position P gain (80).

Type:

int

AddrPositionIGain#

Memory address for position I gain (81).

Type:

int

AddrPositionDGain#

Memory address for position D gain (82).

Type:

int

TorqueEnable#

Value to enable torque (1).

Type:

int

TorqueDisable#

Value to disable torque (0).

Type:

int

CurrentControlMode#

Operating mode for current control (0).

Type:

int

CurrentBasedPositionControlMode#

Operating mode for current-based position control (5).

Type:

int

AddrCurrentTemperature#

Memory address for temperature reading (146).

Type:

int

__init__(self: rby1_sdk.DynamixelBus, dev_name: str) None#

Construct a DynamixelBus instance.

Parameters:

dev_name (str) – Device name (e.g., “/dev/ttyUSB0” on Linux).

Methods

__init__(self, dev_name)

Construct a DynamixelBus instance.

get_motor_states(self, ids)

Get motor states for multiple motors.

get_position_d_gain(self, id)

Get position D gain for a motor.

get_position_i_gain(self, id)

Get position I gain for a motor.

get_position_p_gain(self, id)

Get position P gain for a motor.

get_position_pid_gain(self, id)

Get position PID gains for a motor.

group_fast_sync_read(self, ids, addr, len)

Perform fast synchronous read for multiple motors.

group_fast_sync_read_encoder(self, ids)

Perform fast synchronous read of encoder values.

group_fast_sync_read_operating_mode(self, ...)

Perform fast synchronous read of operating modes.

group_fast_sync_read_torque_enable(self, ids)

Perform fast synchronous read of torque enable states.

group_sync_write_operating_mode(self, ...)

Perform synchronous write of operating modes.

group_sync_write_send_position(self, ...)

Perform synchronous write of goal positions.

group_sync_write_send_torque(self, ...)

Perform synchronous write of torque commands.

group_sync_write_torque_enable(*args, **kwargs)

Overloaded function.

open_port(self)

Open the communication port.

ping(self, id)

Ping a motor to check if it's responding.

read_button_status(self, arg0)

Read button status from a device.

read_encoder(self, id)

Read encoder position for a motor.

read_operating_mode(self, id, use_cache)

Read operating mode for a motor.

read_temperature(self, id)

Read temperature for a motor.

read_torque_enable(self, id)

Read torque enable state for a motor.

send_current(self, id, current)

Send current command to a motor.

send_goal_position(self, id, goal_position)

Send goal position to a motor.

send_operating_mode(self, id, operating_mode)

Send operating mode to a motor.

send_torque(self, id, torque)

Send torque command to a motor.

send_torque_enable(self, id, onoff)

Enable or disable torque for a motor.

send_vibration(self, id, vibration)

Send vibration command to a device.

set_baud_rate(self, baudrate)

Set the communication baudrate.

set_position_d_gain(self, id, d_gain)

Set position D gain for a motor.

set_position_i_gain(self, id, i_gain)

Set position I gain for a motor.

set_position_p_gain(self, id, p_gain)

Set position P gain for a motor.

set_position_pid_gain(*args, **kwargs)

Overloaded function.

set_torque_constant(self, torque_constant)

Set torque constants for motors.

Attributes

class ButtonState#

Bases: pybind11_object

Button state information for gripper devices.

This class represents the state of buttons and triggers on gripper or tool devices.

button#

Button state: 0 (released) or 1 (pressed).

Type:

int

trigger#

Trigger value ranging from 0 to 255.

Type:

int

property button#
property trigger#
class MotorState#

Bases: pybind11_object

Motor state information.

This class represents the current state of a Dynamixel motor including position, velocity, current, and temperature.

torque_enable#

Whether torque is currently enabled.

Type:

bool

position#

Current position [rad].

Type:

float

velocity#

Current velocity [rad/s].

Type:

float

current#

Current current [A].

Type:

float

torque#

Current torque [Nm].

Type:

float

temperature#

Current temperature in degrees Celsius.

Type:

int

property current#
property position#
property temperature#
property torque#
property torque_enable#
property velocity#
class PIDGain#

Bases: pybind11_object

PID gain parameters for position control.

This class represents the proportional, integral, and derivative gains used for position control of Dynamixel motors.

p_gain#

Proportional gain (0-65535).

Type:

int

i_gain#

Integral gain (0-65535).

Type:

int

d_gain#

Derivative gain (0-65535).

Type:

int

property d_gain#
property i_gain#
property p_gain#
get_motor_states(self: rby1_sdk.DynamixelBus, ids: list[int]) list[tuple[int, rby1_sdk.DynamixelBus.MotorState]] | None#

Get motor states for multiple motors.

Parameters:

ids (list[int]) – List of motor IDs.

Returns:

List of (id, motor_state) tuples if successful, None otherwise.

Return type:

list[tuple[int, MotorState]] or None

get_position_d_gain(self: rby1_sdk.DynamixelBus, id: int) int | None#

Get position D gain for a motor.

Parameters:

id (int) – Motor ID.

Returns:

D gain value if successful, None otherwise.

Return type:

int or None

get_position_i_gain(self: rby1_sdk.DynamixelBus, id: int) int | None#

Get position I gain for a motor.

Parameters:

id (int) – Motor ID.

Returns:

I gain value if successful, None otherwise.

Return type:

int or None

get_position_p_gain(self: rby1_sdk.DynamixelBus, id: int) int | None#

Get position P gain for a motor.

Parameters:

id (int) – Motor ID.

Returns:

P gain value if successful, None otherwise.

Return type:

int or None

get_position_pid_gain(self: rby1_sdk.DynamixelBus, id: int) rby1_sdk.DynamixelBus.PIDGain | None#

Get position PID gains for a motor.

Parameters:

id (int) – Motor ID.

Returns:

PIDGain struct if successful, None otherwise.

Return type:

PIDGain or None

group_fast_sync_read(self: rby1_sdk.DynamixelBus, ids: list[int], addr: int, len: int) list[tuple[int, int]] | None#

Perform fast synchronous read for multiple motors.

Parameters:
  • ids (list[int]) – List of motor IDs.

  • addr (int) – Memory address to read from.

  • len (int) – Number of bytes to read.

Returns:

List of (id, value) tuples if successful, None otherwise.

Return type:

list[tuple[int, int]] or None

group_fast_sync_read_encoder(self: rby1_sdk.DynamixelBus, ids: list[int]) list[tuple[int, float]] | None#

Perform fast synchronous read of encoder values.

Parameters:

ids (list[int]) – List of motor IDs.

Returns:

List of (id, encoder_value) tuples if successful, None otherwise.

Return type:

list[tuple[int, float]] or None

group_fast_sync_read_operating_mode(self: rby1_sdk.DynamixelBus, ids: list[int], use_cache: bool) list[tuple[int, int]] | None#

Perform fast synchronous read of operating modes.

Parameters:
  • ids (list[int]) – List of motor IDs.

  • use_cache (bool, optional) – Whether to use cached values. Default is False.

Returns:

List of (id, operating_mode) tuples if successful, None otherwise.

Return type:

list[tuple[int, int]] or None

group_fast_sync_read_torque_enable(self: rby1_sdk.DynamixelBus, ids: list[int]) list[tuple[int, int]] | None#

Perform fast synchronous read of torque enable states.

Parameters:

ids (list[int]) – List of motor IDs.

Returns:

List of (id, torque_enable) tuples if successful, None otherwise.

Return type:

list[tuple[int, int]] or None

group_sync_write_operating_mode(self: rby1_sdk.DynamixelBus, id_and_mode_vector: list[tuple[int, int]]) None#

Perform synchronous write of operating modes.

Parameters:

id_and_mode_vector (list[tuple[int, int]]) – List of (id, mode) tuples.

group_sync_write_send_position(self: rby1_sdk.DynamixelBus, id_and_position_vector: list[tuple[int, float]]) None#

Perform synchronous write of goal positions.

Parameters:

id_and_position_vector (list[tuple[int, int]]) – List of (id, position) tuples.

group_sync_write_send_torque(self: rby1_sdk.DynamixelBus, id_and_torque_vector: list[tuple[int, float]]) None#

Perform synchronous write of torque commands.

Parameters:

id_and_torque_vector (list[tuple[int, float]]) – List of (id, torque) tuples.

group_sync_write_torque_enable(*args, **kwargs)#

Overloaded function.

  1. group_sync_write_torque_enable(self: rby1_sdk.DynamixelBus, id_and_enable_vector: list[tuple[int, int]]) -> None

Perform synchronous write of torque enable states.

Parameters:

id_and_enable_vector (list[tuple[int, int]]) – List of (id, enable) tuples.

  1. group_sync_write_torque_enable(self: rby1_sdk.DynamixelBus, ids: list[int], enable: int) -> None

Perform synchronous write of torque enable states.

Parameters:
  • ids (list[int]) – List of motor IDs.

  • enable (int) – Enable value (1=enabled, 0=disabled).

open_port(self: rby1_sdk.DynamixelBus) bool#

Open the communication port.

Returns:

True if port opened successfully, False otherwise.

Return type:

bool

ping(self: rby1_sdk.DynamixelBus, id: int) bool#

Ping a motor to check if it’s responding.

Parameters:

id (int) – Motor ID to ping.

Returns:

True if motor responds, False otherwise.

Return type:

bool

read_button_status(self: rby1_sdk.DynamixelBus, arg0: int) tuple[int, rby1_sdk.DynamixelBus.ButtonState] | None#

Read button status from a device.

Parameters:

id (int) – Device ID to read from.

Returns:

Tuple of (id, button_state) if successful, None otherwise.

Return type:

tuple[int, ButtonState] or None

read_encoder(self: rby1_sdk.DynamixelBus, id: int) float | None#

Read encoder position for a motor.

Parameters:

id (int) – Motor ID.

Returns:

Encoder position in radians if successful, None otherwise.

Return type:

float or None

read_operating_mode(self: rby1_sdk.DynamixelBus, id: int, use_cache: bool) int | None#

Read operating mode for a motor.

Parameters:
  • id (int) – Motor ID.

  • use_cache (bool, optional) – Whether to use cached value. Default is False.

Returns:

Operating mode value if successful, None otherwise.

Return type:

int or None

read_temperature(self: rby1_sdk.DynamixelBus, id: int) int | None#

Read temperature for a motor.

Parameters:

id (int) – Motor ID.

Returns:

Temperature in degrees Celsius if successful, None otherwise.

Return type:

int or None

read_torque_enable(self: rby1_sdk.DynamixelBus, id: int) int | None#

Read torque enable state for a motor.

Parameters:

id (int) – Motor ID.

Returns:

Torque state (1=enabled, 0=disabled) if successful, None otherwise.

Return type:

int or None

send_current(self: rby1_sdk.DynamixelBus, id: int, current: float) None#

Send current command to a motor.

Parameters:
  • id (int) – Motor ID.

  • current (float) – Current value [A].

send_goal_position(self: rby1_sdk.DynamixelBus, id: int, goal_position: int) None#

Send goal position to a motor.

Parameters:
  • id (int) – Motor ID.

  • goal_position (int) – Goal position in encoder units.

send_operating_mode(self: rby1_sdk.DynamixelBus, id: int, operating_mode: int) bool#

Send operating mode to a motor.

Parameters:
  • id (int) – Motor ID.

  • mode (int) – Operating mode value.

Returns:

True if successful, False otherwise.

Return type:

bool

send_torque(self: rby1_sdk.DynamixelBus, id: int, torque: float) None#

Send torque command to a motor.

Parameters:
  • id (int) – Motor ID.

  • joint_torque (float) – Torque value [Nm].

send_torque_enable(self: rby1_sdk.DynamixelBus, id: int, onoff: int) None#

Enable or disable torque for a motor.

Parameters:
  • id (int) – Motor ID.

  • onoff (int) – Torque state: 1 (enable) or 0 (disable).

send_vibration(self: rby1_sdk.DynamixelBus, id: int, vibration: int) None#

Send vibration command to a device.

Parameters:
  • id (int) – Device ID.

  • level (int) – Vibration level (0-255).

set_baud_rate(self: rby1_sdk.DynamixelBus, baudrate: int) bool#

Set the communication baudrate.

Parameters:

baudrate (int) – Baudrate value (e.g., 2000000).

Returns:

True if baudrate set successfully, False otherwise.

Return type:

bool

set_position_d_gain(self: rby1_sdk.DynamixelBus, id: int, d_gain: int) None#

Set position D gain for a motor.

Parameters:
  • id (int) – Motor ID.

  • d_gain (int) – D gain value (0-65535).

set_position_i_gain(self: rby1_sdk.DynamixelBus, id: int, i_gain: int) None#

Set position I gain for a motor.

Parameters:
  • id (int) – Motor ID.

  • i_gain (int) – I gain value (0-65535).

set_position_p_gain(self: rby1_sdk.DynamixelBus, id: int, p_gain: int) None#

Set position P gain for a motor.

Parameters:
  • id (int) – Motor ID.

  • p_gain (int) – P gain value (0-65535).

set_position_pid_gain(*args, **kwargs)#

Overloaded function.

  1. set_position_pid_gain(self: rby1_sdk.DynamixelBus, id: int, p_gain: Optional[int], i_gain: Optional[int], d_gain: Optional[int]) -> None

Set position PID gains for a motor.

Parameters:
  • id (int) – Motor ID.

  • p_gain (int or None, optional) – P gain value (0-65535). If None, current value is preserved.

  • i_gain (int or None, optional) – I gain value (0-65535). If None, current value is preserved.

  • d_gain (int or None, optional) – D gain value (0-65535). If None, current value is preserved.

  1. set_position_pid_gain(self: rby1_sdk.DynamixelBus, id: int, pid_gain: rby1_sdk.DynamixelBus.PIDGain) -> None

Set position PID gains for a motor using PIDGain struct.

Parameters:
  • id (int) – Motor ID.

  • pid_gain (PIDGain) – PIDGain struct containing P, I, and D values.

set_torque_constant(self: rby1_sdk.DynamixelBus, torque_constant: list[float]) None#

Set torque constants for motors.

Parameters:

torque_constant (list[float]) – List of torque constants for each motor.

AddrCurrentTemperature = 146#
AddrGoalCurrent = 102#
AddrGoalPosition = 116#
AddrGoalVibrationLevel = 102#
AddrOperatingMode = 11#
AddrPositionDGain = 80#
AddrPositionIGain = 82#
AddrPositionPGain = 84#
AddrPresentButtonState = 132#
AddrPresentCurrent = 126#
AddrPresentPosition = 132#
AddrPresentVelocity = 128#
AddrTorqueEnable = 64#
CurrentBasedPositionControlMode = 5#
CurrentControlMode = 0#
DefaultBaudrate = 2000000#
ProtocolVersion = 2.0#
TorqueDisable = 0#
TorqueEnable = 1#