class documentation

class Piper:

Constructor: Piper(can_iface)

View In Hierarchy

Interface for controlling the AgileX PiPER robotic arm via CAN bus.

This class provides methods for controlling joint positions, enabling/disabling joints, and reading feedback from the robotic arm through the CAN bus interface.

Parameters
can_ifaceCAN interface name (e.g., 'can0')
Method __enter__ Enter context manager.
Method __exit__ Exit context manager and shutdown CAN bus.
Method __init__ Initialize Piper with CAN interface.
Method disable_all_joints Disable all joints simultaneously.
Method disable_gripper Disable gripper control.
Method disable_joint Disable a specific joint.
Method enable_all_joints Enable or disable all joints simultaneously.
Method enable_gripper Enable or disable gripper control.
Method enable_joint Enable or disable a specific joint.
Method read_all_joint_feedbacks Read current position feedback from all 6 joints.
Method read_all_motor_info_bs Read motor information from all 6 joints.
Method read_gripper_feedback Read position feedback from the gripper.
Method read_message Read a single message from the CAN bus.
Method set_all_joint_configs Set the configuration of all joints.
Method set_end_pose_control Set position and rotation control of end-effector pose.
Method set_end_pose_control_ry Set roll and yaw rotations control of end-effector pose.
Method set_end_pose_control_xy Set X and Y positions control of end-effector pose.
Method set_end_pose_control_zp Set Z position and pitch rotation control of end-effector pose.
Method set_gripper_control Control gripper position and effort.
Method set_joint_config Set the configuration of a specific joint.
Method set_joint_control Set position control for all 6 joints simultaneously.
Method set_joint_control_12 Set position control for joints 1 and 2.
Method set_joint_control_34 Set position control for joints 3 and 4.
Method set_joint_control_56 Set position control for joints 5 and 6.
Method set_motion_control_b Set motion control parameters for the robotic arm.
Instance Variable bus Undocumented
def __enter__(self) -> Self:

Enter context manager.

def __exit__(self, _exc_type: type[BaseException] | None, _exc_val: BaseException | None, _exc_tb: TracebackType | None):

Exit context manager and shutdown CAN bus.

def __init__(self, can_iface: str):

Initialize Piper with CAN interface.

def disable_all_joints(self):

Disable all joints simultaneously.

def disable_gripper(self):

Disable gripper control.

def disable_joint(self, joint_id: EnableJointMessage.JointId):

Disable a specific joint.

Parameters
joint_id:EnableJointMessage.JointIdJoint ID (1-6) or 7 for all joints
def enable_all_joints(self, *, enable: bool = True):

Enable or disable all joints simultaneously.

Parameters
enable:boolTrue to enable, False to disable
def enable_gripper(self, *, enable: bool = True):

Enable or disable gripper control.

Parameters
enable:boolTrue to enable, False to disable
def enable_joint(self, joint_id: EnableJointMessage.JointId, *, enable: bool = True):

Enable or disable a specific joint.

Parameters
joint_id:EnableJointMessage.JointIdJoint ID (1-6) or 7 for all joints
enable:boolTrue to enable, False to disable
def read_all_joint_feedbacks(self) -> list[int]:

Read current position feedback from all 6 joints.

Blocks until feedback is received from all joints.

Returns
list[int]List of 6 joint positions [joint1, joint2, joint3, joint4, joint5, joint6]
def read_all_motor_info_bs(self) -> list[MotorInfoBMessage]:

Read motor information from all 6 joints.

Blocks until motor info is received from all joints.

Returns
list[MotorInfoBMessage]List of 6 MotorInfoBMessage objects containing status and diagnostic info
def read_gripper_feedback(self) -> GripperFeedbackMessage:

Read position feedback from the gripper.

Blocks until gripper feedback is received.

Returns
GripperFeedbackMessageA GripperFeedbackMessage containing the current gripper position.
def read_message(self) -> ReceiveMessage:

Read a single message from the CAN bus.

Returns
ReceiveMessageParsed message object (JointFeedback, GripperFeedback, MotorInfo, or Unknown)
def set_all_joint_configs(self, *, set_zero: bool = False, clear_error: bool = False):

Set the configuration of all joints.

Parameters
set_zero:boolWhether to set the current joint position as the zero position
clear_error:boolWhether to clear the current joint error codes
def set_end_pose_control(self, x: int, y: int, z: int, pitch: int, roll: int, yaw: int):

Set position and rotation control of end-effector pose.

Parameters
x:intTarget X position in 0.001 mm.
y:intTarget Y position in 0.001 mm.
z:intTarget Z position in 0.001 mm.
pitch:intTarget pitch rotation in 0.001 degrees.
roll:intTarget roll rotation in 0.001 degrees.
yaw:intTarget yaw rotation in 0.001 degrees.
def set_end_pose_control_ry(self, roll: int, yaw: int):

Set roll and yaw rotations control of end-effector pose.

Parameters
roll:intTarget roll rotation in 0.001 degrees.
yaw:intTarget yaw rotation in 0.001 degrees.
def set_end_pose_control_xy(self, x: int, y: int):

Set X and Y positions control of end-effector pose.

Parameters
x:intTarget X position in 0.001 mm.
y:intTarget Y position in 0.001 mm.
def set_end_pose_control_zp(self, z: int, pitch: int):

Set Z position and pitch rotation control of end-effector pose.

Parameters
z:intTarget Z position in 0.001 mm.
pitch:intTarget pitch rotation in 0.001 degrees.
def set_gripper_control(self, position: int, effort: int, *, enable: bool = True, clear_error: bool = False, set_zero: bool = False):

Control gripper position and effort.

Parameters
position:intTarget gripper position
effort:intEffort/force to apply
enable:boolEnable gripper control
clear_error:boolClear any error state
set_zero:boolSet current position as zero reference
def set_joint_config(self, joint_id: JointConfigMessage.JointId, *, set_zero: bool = False, clear_error: bool = False):

Set the configuration of a specific joint.

Parameters
joint_id:JointConfigMessage.JointIdJoint ID (1-6 for individual joints, 7 for all joints)
set_zero:boolWhether to set the current joint position as the zero position
clear_error:boolWhether to clear the current joint error codes
def set_joint_control(self, joint_1: int, joint_2: int, joint_3: int, joint_4: int, joint_5: int, joint_6: int):

Set position control for all 6 joints simultaneously.

Parameters
joint_1:intTarget position for joint 1
joint_2:intTarget position for joint 2
joint_3:intTarget position for joint 3
joint_4:intTarget position for joint 4
joint_5:intTarget position for joint 5
joint_6:intTarget position for joint 6
def set_joint_control_12(self, joint_1: int, joint_2: int):

Set position control for joints 1 and 2.

Parameters
joint_1:intTarget position for joint 1
joint_2:intTarget position for joint 2
def set_joint_control_34(self, joint_3: int, joint_4: int):

Set position control for joints 3 and 4.

Parameters
joint_3:intTarget position for joint 3
joint_4:intTarget position for joint 4
def set_joint_control_56(self, joint_5: int, joint_6: int):

Set position control for joints 5 and 6.

Parameters
joint_5:intTarget position for joint 5
joint_6:intTarget position for joint 6
def set_motion_control_b(self, move_mode: MotionControlBMessage.MoveMode, move_speed_rate: int, *, control_mode: MotionControlBMessage.ControlMode = 'can'):

Set motion control parameters for the robotic arm.

Parameters
move_mode:MotionControlBMessage.MoveModeMotion control mode ('joint' or other modes)
move_speed_rate:intSpeed rate for movement (0-100)
control_mode:MotionControlBMessage.ControlModeControl mode ('can' by default)
bus =

Undocumented