Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 0 additions & 4 deletions examples/machine_vision/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,3 @@ This example assumes you have a working machine vison camera. The camera should
The example also requires you to measure the x, y, z axis offset of the camera's position relative to Eva's base and the distance between the camera and the 2D plane where the objects will be detected. This example assumes that the camera's axis are aligned with Eva's.

![Positional picture should be here!](camera_example.png)

## Supported Version

Tested to work with Eva software verision 2.1.x
16 changes: 8 additions & 8 deletions examples/machine_vision/evaCamera.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from automata import Eva
from evasdk import Eva


XYPosition = (float, float)
Expand All @@ -18,11 +18,11 @@ class EvaCamera:
"""
def __init__(self, eva: Eva, camera_relative_position: XYZPosition, camera_to_object_distance: float):
self.__eva = eva
self.__eva_offset_position_x = camera_relative_position[0]
self.__eva_offset_position_x = camera_relative_position[0]
self.__eva_offset_position_y = camera_relative_position[1]
self.__eva_offset_position_z = camera_relative_position[2] - camera_to_object_distance


def move_to_camera_item(self, camera_item_postion: XYPosition):
"""
Move Eva's end effector to the item position. Using the offset between
Expand All @@ -37,14 +37,14 @@ def move_to_camera_item(self, camera_item_postion: XYPosition):
eva_relative_x = self.__eva_offset_position_x + camera_item_x
eva_relative_y = self.__eva_offset_position_y + camera_item_y
eva_relative_z = self.__eva_offset_position_z
item_position = {'x': eva_relative_x, 'y': eva_relative_y, 'z': eva_relative_z}
item_position = {'x': eva_relative_x, 'y': eva_relative_y, 'z': eva_relative_z}

print(f'moving to item position {item_position}')
with self.__eva.lock():
to_item_joint_angles = self.__eva.calc_inverse_kinematics(POSE_GUESS, item_position, DEFAULT_END_EFFECTOR_ORIENTATION)
self.__eva.control_go_to(to_item_joint_angles['ik']['joints'])
print("in item position")

print("in item position")


def in_position_action(self):
Expand All @@ -62,9 +62,9 @@ def move_home(self):
"""
print("moving home")
with self.__eva.lock():
self.__eva.control_go_to(POSE_HOME)
self.__eva.control_go_to(POSE_HOME)

print("in home position")
print("in home position")


def read_from_camera() -> XYPosition:
Expand Down