rby1_sdk.upc#
Module for controlling and communicating with devices.
Provides utilities for controlling master arm and other devices.
Functions
|
initialize_device(device_name) |
Classes
Master arm control interface. |
- class MasterArm#
Bases:
pybind11_objectMaster arm control interface.
This class provides control interface for a master arm device with 14 degrees of freedom, including joint control, gravity compensation, and button/trigger input handling.
- class ControlInput#
Bases:
pybind11_objectMaster arm control input.
This class represents the control input for the master arm including target operating modes, positions, and torques.
- target_operating_mode#
Target operating modes for each joint.
- Type:
numpy.ndarray, shape (14,), dtype=int32
- target_position#
Target positions for each joint [rad].
- Type:
numpy.ndarray, shape (14,), dtype=float64
- target_torque#
Target torques for each joint [Nm].
- Type:
numpy.ndarray, shape (14,), dtype=float64
- property target_operating_mode#
- property target_position#
- property target_torque#
- class State#
Bases:
pybind11_objectMaster arm state information.
This class represents the current state of the master arm including joint positions, velocities, torques, and tool states.
- q_joint#
Joint positions [rad].
- Type:
numpy.ndarray, shape (14,), dtype=float64
- qvel_joint#
Joint velocities [rad/s].
- Type:
numpy.ndarray, shape (14,), dtype=float64
- torque_joint#
Joint torques [Nm].
- Type:
numpy.ndarray, shape (14,), dtype=float64
- gravity_term#
Gravity compensation terms.
- Type:
numpy.ndarray, shape (14,), dtype=float64
- operating_mode#
Operating modes for each joint.
- Type:
numpy.ndarray, shape (14,), dtype=int32
- button_right#
Right tool button and trigger state.
- Type:
- button_left#
Left tool button and trigger state.
- Type:
- T_right#
Right tool transformation matrix (SE(3)) with respect to the master arm base.
- Type:
numpy.ndarray, shape (4, 4), dtype=float64
- T_left#
Left tool transformation matrix (SE(3)) with respect to the master arm base.
- Type:
numpy.ndarray, shape (4, 4), dtype=float64
- property T_left#
- property T_right#
- property button_left#
- property button_right#
- property gravity_term#
- property operating_mode#
- property q_joint#
- property qvel_joint#
- property target_position#
- property torque_joint#
- disable_torque(self: rby1_sdk.upc.MasterArm) bool#
Disable torque of motors
- enable_torque(self: rby1_sdk.upc.MasterArm) bool#
Enable torque of motors
- initialize(self: rby1_sdk.upc.MasterArm, verbose: bool = False) list[int]#
Initialize the master arm and detect active devices.
- set_control_period(self: rby1_sdk.upc.MasterArm, control_period: float) None#
Set the control update period.
- Parameters:
control_period (float) – Control period in seconds.
- set_model_path(self: rby1_sdk.upc.MasterArm, model_path: str) None#
Set the path to the URDF model file.
- Parameters:
model_path (str) – Path to the URDF model file.
- set_torque_constant(self: rby1_sdk.upc.MasterArm, torque_constant: Annotated[list[float], FixedSize(14)]) None#
Set torque constant.
- Parameters:
torque_constant (numpy.ndarray (14, ))
model_path (str) – Path to the URDF model file.
- start_control(self: rby1_sdk.upc.MasterArm, control: Callable[[rby1_sdk.upc.MasterArm.State], rby1_sdk.upc.MasterArm.ControlInput]) bool#
Start the control loop.
- Parameters:
control (callable, optional) – Control callback function that takes State and returns ControlInput. If None, no control is applied.
- Return type:
Examples
>>> master_arm = rby.upc.MasterArm(rby.upc.MasterArmDeviceName) >>> master_arm.set_model_path("model.urdf") # path/to/master_arm_model.urdf >>> master_arm.set_control_period(0.01) >>> active_ids = master_arm.initialize(verbose=True) >>> if len(active_ids) != rby.upc.MasterArm.DeviceCount: ... print("Error: Mismatch in the number of devices detected for RBY Master Arm.") ... exit(1) >>> >>> def control(state: rby.upc.MasterArm.State): ... with np.printoptions(suppress=True, precision=3, linewidth=300): ... print(f"--- {datetime.datetime.now().time()} ---") ... print(f"q: {state.q_joint}") ... print(f"g: {state.gravity_term}") ... print( ... f"right: {state.button_right.button}, left: {state.button_left.button}" ... ) ... input = rby.upc.MasterArm.ControlInput() ... input.target_operating_mode.fill(rby.DynamixelBus.CurrentControlMode) ... input.target_torque = state.gravity_term ... return input >>> >>> master_arm.start_control(control) >>> time.sleep(100)
- stop_control(self: rby1_sdk.upc.MasterArm, torque_disable: bool = False) bool#
Stop the control loop.
- DOF = 14#
- DeviceCount = 16#
- LeftToolId = 129#
- MaximumTorque = 4.0#
- RightToolId = 128#
- TorqueScaling = 0.5#