move_xyz
Description
Moves the N9 robot arm such that the end-effector (EE) is at the target (x, y, z) position in units of mm. The target position must be in the robot's work envelope (i.e., must have a valid inverse-kinematic solution). The EE may be either the gripper, pipette tip probe, or may be selected arbitrarily using the tool_offset parameter. The tool_orientation parameter may be used to set the angle of the gripper joint.
During the move, velocities of each axis are scaled such that all joints start and stop moving together. The velocity value for the move represents the maximum velocity of the axis that is moving the largest number of counts. The maximum velocities of all other moving axes are correspondingly scaled down.
Signature
move_xyz(self, x: float, y: float, z: float, tool_offset: Optional[List[float]] = None, tool_orientation: Optional[float] = None, pipette_tip_offset: bool = False, shoulder_preference: int = 0, vel: Optional[int] = None, accel: Optional[int] = None, wait: bool = True) -> CmdToken
Parameters
x: int
The target x-position of the EE in units of mm.
y: int
The target y-position of the EE in units of mm.
z: int
The target z-position of the EE in units of mm.
tool_offset: List[float], optional
A list of 3 floats corresponding the length of the tool in the x, y, and z axes.
tool_orientation: int
The rotation of the gripper with respect to the global Cartesian x-axis in units of degrees.
pipette_tip_offset: bool
If True, the EE is considered to be the pipette tip probe, otherwise it is the center of the N9 gripper.
shoulder_preference: int
{NorthC9.SHOULDER_CENTER, NorthC9.SHOULDER_OUT}
Determines the kinematic solution to achieve the target position. If SHOULDER_CENTER, the N9 will achieve the target position such that the shoulder joint is closer to the Cartesian y-axis. If SHOULDER_OUT, the target position will be achieved with the opposite pose.
vel: int, optional
Max velocity of the move in units of counts per second [0, 100000]. Values [0, 100] are interpreted as a percentage of the maximum velocity (100,000 cts/s). If the accel parameter is not given, the acceleration will be set to 10x the velocity in units of cts/s². Note velocity scaling may occur, as explained in the function description.
accel: int, optional
Constant acceleration of the axis to reach the given velocity, in units of counts per second² [0, 500000]. Values [0, 100] are interpreted as a percentage of the maximum acceleration (500,000 cts/s²).
wait: bool, optional
If True, this command blocks until the move is finished.
Returns
CmdToken
A CmdToken object that can be used to follow up on the status of the move or wait for it to finish if wait = False.
Example