PreciseFlex PF400 and PF3400 robots#

Connection: ethernet

%load_ext autoreload
%autoreload 2
from pylabrobot.arms.scara import ExperimentalSCARA
from pylabrobot.arms.precise_flex.pf_400 import PreciseFlex400Backend

from pylabrobot.arms.precise_flex.coords import PreciseFlexCartesianCoords
from pylabrobot.arms.precise_flex.joints import PreciseFlexJointCoords
from pylabrobot.resources import Coordinate, Rotation
backend = PreciseFlex400Backend(host="192.168.0.1", port=10100, has_rail=False)
arm = ExperimentalSCARA(backend=backend)
await arm.setup(skip_home=False)

Granular Robot control#

Gripper Control#

The gripper can be controlled manually as follows:

await arm.close_gripper(gripper_width=80)
await arm.open_gripper(gripper_width=120)
await backend.is_gripper_closed()

Movement#

You can also arbitrarily move the arm to cartesian coordinates as well as joint coordinates:

Warning

Depending on the current position, moving to a joint position might actually cause the arm to collide with its base! Be careful when using joint coordinates.

location = PreciseFlexJointCoords(
  base=99.981,
  shoulder=-36.206,
  elbow=83.063,
  wrist=-331.7,
  gripper=126.084,
  rail=0.0
)
await arm.move_to(location)
location = PreciseFlexCartesianCoords(
  location=Coordinate(x=290, y=659, z=100),
  rotation=Rotation(x=-180.0, y=90.0, z=84.804)
)
await arm.move_to(location)

Getting current location#

Get the joint angles of the robot’s arm, including the rails if applicable and the gripper width:

await arm.get_joint_position()

Get the cartesian coordinates of the robot’s end effector:

await arm.get_cartesian_position()

Teaching positions using free mode#

Use “free mode” to manually move the robot’s arm to a desired position, and then read the current cartesian coordinates. You can use the cartesian coordinates to programmatically move the arm to that position later.

await backend.activate_free_mode()
await arm.get_cartesian_position()
await backend.deactivate_free_mode()

Plate Movement#

Below is an example of picking up and placing a plate using cartesian coordinates. You can call move_to in between to move to other locations as needed.

location = PreciseFlexCartesianCoords(
  location=Coordinate(x=650.74, y=-345.922, z=5.05),
  rotation=Rotation(x=180.0, y=90.0, z=-9.921)
)
await arm.pick_up_resource(
  location,
  plate_width=125,
)
await arm.drop_resource(location)

Miscellaneous commands#

Move the arm to its predefined home/safe position:

await arm.move_to_safe()

Home the arm:

await arm.home()

Stop any ongoing movement of the arm:

await arm.halt()