From cfa995b7f94223bfb2166ae835871f8c9100bbcc Mon Sep 17 00:00:00 2001 From: charlesworth Date: Thu, 5 Mar 2020 17:11:22 +0000 Subject: [PATCH] updated the machine vision example to work with 3.x.x --- examples/machine_vision/README.md | 4 ---- examples/machine_vision/evaCamera.py | 16 ++++++++-------- 2 files changed, 8 insertions(+), 12 deletions(-) diff --git a/examples/machine_vision/README.md b/examples/machine_vision/README.md index 8a9de31..74fcb01 100644 --- a/examples/machine_vision/README.md +++ b/examples/machine_vision/README.md @@ -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 \ No newline at end of file diff --git a/examples/machine_vision/evaCamera.py b/examples/machine_vision/evaCamera.py index 0105458..ac04780 100644 --- a/examples/machine_vision/evaCamera.py +++ b/examples/machine_vision/evaCamera.py @@ -1,4 +1,4 @@ -from automata import Eva +from evasdk import Eva XYPosition = (float, float) @@ -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 @@ -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): @@ -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: