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 | CAN 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 |
Disable all joints simultaneously. |
Method | disable |
Disable gripper control. |
Method | disable |
Disable a specific joint. |
Method | enable |
Enable or disable all joints simultaneously. |
Method | enable |
Enable or disable gripper control. |
Method | enable |
Enable or disable a specific joint. |
Method | read |
Read current position feedback from all 6 joints. |
Method | read |
Read motor information from all 6 joints. |
Method | read |
Read position feedback from the gripper. |
Method | read |
Read a single message from the CAN bus. |
Method | set |
Set the configuration of all joints. |
Method | set |
Set position and rotation control of end-effector pose. |
Method | set |
Set roll and yaw rotations control of end-effector pose. |
Method | set |
Set X and Y positions control of end-effector pose. |
Method | set |
Set Z position and pitch rotation control of end-effector pose. |
Method | set |
Control gripper position and effort. |
Method | set |
Set the configuration of a specific joint. |
Method | set |
Set position control for all 6 joints simultaneously. |
Method | set |
Set position control for joints 1 and 2. |
Method | set |
Set position control for joints 3 and 4. |
Method | set |
Set position control for joints 5 and 6. |
Method | set |
Set motion control parameters for the robotic arm. |
Instance Variable | bus |
Undocumented |
type[ BaseException] | None
, _exc_val: BaseException | None
, _exc_tb: TracebackType | None
):
¶
Exit context manager and shutdown CAN bus.
Disable a specific joint.
Parameters | |
jointEnableJointMessage.JointId | Joint ID (1-6) or 7 for all joints |
Enable or disable a specific joint.
Parameters | |
jointEnableJointMessage.JointId | Joint ID (1-6) or 7 for all joints |
enable:bool | True to enable, False to disable |
Read current position feedback from all 6 joints.
Blocks until feedback is received from all joints.
Returns | |
list[ | List of 6 joint positions [joint1, joint2, joint3, joint4, joint5, joint6] |
Read motor information from all 6 joints.
Blocks until motor info is received from all joints.
Returns | |
list[ | List of 6 MotorInfoBMessage objects containing status and diagnostic info |
Read position feedback from the gripper.
Blocks until gripper feedback is received.
Returns | |
GripperFeedbackMessage | A GripperFeedbackMessage containing the current gripper position. |
Read a single message from the CAN bus.
Returns | |
ReceiveMessage | Parsed message object (JointFeedback, GripperFeedback, MotorInfo, or Unknown) |
Set the configuration of all joints.
Parameters | |
setbool | Whether to set the current joint position as the zero position |
clearbool | Whether to clear the current joint error codes |
Set position and rotation control of end-effector pose.
Parameters | |
x:int | Target X position in 0.001 mm. |
y:int | Target Y position in 0.001 mm. |
z:int | Target Z position in 0.001 mm. |
pitch:int | Target pitch rotation in 0.001 degrees. |
roll:int | Target roll rotation in 0.001 degrees. |
yaw:int | Target yaw rotation in 0.001 degrees. |
Set roll and yaw rotations control of end-effector pose.
Parameters | |
roll:int | Target roll rotation in 0.001 degrees. |
yaw:int | Target yaw rotation in 0.001 degrees. |
Set X and Y positions control of end-effector pose.
Parameters | |
x:int | Target X position in 0.001 mm. |
y:int | Target Y position in 0.001 mm. |
Set Z position and pitch rotation control of end-effector pose.
Parameters | |
z:int | Target Z position in 0.001 mm. |
pitch:int | Target pitch rotation in 0.001 degrees. |
int
, effort: int
, *, enable: bool
= True, clear_error: bool
= False, set_zero: bool
= False):
¶
Control gripper position and effort.
Parameters | |
position:int | Target gripper position |
effort:int | Effort/force to apply |
enable:bool | Enable gripper control |
clearbool | Clear any error state |
setbool | Set current position as zero reference |
JointConfigMessage.JointId
, *, set_zero: bool
= False, clear_error: bool
= False):
¶
Set the configuration of a specific joint.
Parameters | |
jointJointConfigMessage.JointId | Joint ID (1-6 for individual joints, 7 for all joints) |
setbool | Whether to set the current joint position as the zero position |
clearbool | Whether to clear the current joint error codes |
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 | |
jointint | Target position for joint 1 |
jointint | Target position for joint 2 |
jointint | Target position for joint 3 |
jointint | Target position for joint 4 |
jointint | Target position for joint 5 |
jointint | Target position for joint 6 |
Set position control for joints 1 and 2.
Parameters | |
jointint | Target position for joint 1 |
jointint | Target position for joint 2 |
Set position control for joints 3 and 4.
Parameters | |
jointint | Target position for joint 3 |
jointint | Target position for joint 4 |
Set position control for joints 5 and 6.
Parameters | |
jointint | Target position for joint 5 |
jointint | Target position for joint 6 |
MotionControlBMessage.MoveMode
, move_speed_rate: int
, *, control_mode: MotionControlBMessage.ControlMode
= 'can'):
¶
Set motion control parameters for the robotic arm.
Parameters | |
moveMotionControlBMessage.MoveMode | Motion control mode ('joint' or other modes) |
moveint | Speed rate for movement (0-100) |
controlMotionControlBMessage.ControlMode | Control mode ('can' by default) |