-
Notifications
You must be signed in to change notification settings - Fork 51
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
516fa82
commit 0e0ec81
Showing
3 changed files
with
316 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,16 @@ | ||
import asyncio | ||
from viam.rpc.server import Server | ||
|
||
from module_arm import ModuleArm | ||
|
||
|
||
async def main(): | ||
srv = Server([ModuleArm("moduleArm")]) | ||
await srv.serve() | ||
|
||
|
||
if __name__ == "__main__": | ||
try: | ||
asyncio.run(main()) | ||
except: | ||
pass |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,83 @@ | ||
import asyncio | ||
from typing import Any, Dict, Optional, Tuple | ||
from viam.components.arm import Arm, JointPositions, KinematicsFileFormat, Pose | ||
from viam.operations import run_with_operation | ||
|
||
|
||
class ModuleArm(Arm): | ||
# Subclass the Viam Arm component and implement the required functions | ||
|
||
def __init__(self, name: str): | ||
# Starting position | ||
self.position = Pose( | ||
x=0, | ||
y=0, | ||
z=0, | ||
o_x=0, | ||
o_y=0, | ||
o_z=1, | ||
theta=0, | ||
) | ||
|
||
# Starting joint positions | ||
self.joint_positions = JointPositions(values=[0, 0, 0, 0, 0, 0]) | ||
self.is_stopped = True | ||
super().__init__(name) | ||
|
||
async def get_end_position(self, extra: Optional[Dict[str, Any]] = None, **kwargs) -> Pose: | ||
return self.position | ||
|
||
@run_with_operation | ||
async def move_to_position( | ||
self, | ||
pose: Pose, | ||
extra: Optional[Dict[str, Any]] = None, | ||
**kwargs, | ||
): | ||
operation = self.get_operation(kwargs) | ||
|
||
self.is_stopped = False | ||
self.position = pose | ||
|
||
# Simulate the length of time it takes for the arm to move to its new position | ||
for x in range(10): | ||
await asyncio.sleep(1) | ||
|
||
# Check if the operation is cancelled and, if it is, stop the arm's motion | ||
if await operation.is_cancelled(): | ||
await self.stop() | ||
break | ||
|
||
self.is_stopped = True | ||
|
||
async def get_joint_positions(self, extra: Optional[Dict[str, Any]] = None, **kwargs) -> JointPositions: | ||
return self.joint_positions | ||
|
||
@run_with_operation | ||
async def move_to_joint_positions(self, positions: JointPositions, extra: Optional[Dict[str, Any]] = None, **kwargs): | ||
operation = self.get_operation(kwargs) | ||
|
||
self.is_stopped = False | ||
self.joint_positions = positions | ||
|
||
# Simulate the length of time it takes for the arm to move to its new joint position | ||
for x in range(10): | ||
await asyncio.sleep(1) | ||
|
||
# Check if the operation is cancelled and, if it is, stop the arm's motion | ||
if await operation.is_cancelled(): | ||
await self.stop() | ||
break | ||
|
||
self.is_stopped = True | ||
|
||
async def stop(self, extra: Optional[Dict[str, Any]] = None, **kwargs): | ||
self.is_stopped = True | ||
|
||
async def is_moving(self) -> bool: | ||
return not self.is_stopped | ||
|
||
def get_kinematics(self) -> Tuple[KinematicsFileFormat.ValueType, bytes]: | ||
with open("./xarm6_kinematics.json", mode="rb") as f: | ||
file_data = f.read() | ||
return (KinematicsFileFormat.KINEMATICS_FILE_FORMAT_SVA, file_data) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,217 @@ | ||
{ | ||
"name": "xArm6", | ||
"links": [ | ||
{ | ||
"id": "base", | ||
"parent": "world", | ||
"translation": { | ||
"x": 0, | ||
"y": 0, | ||
"z": 0 | ||
} | ||
}, | ||
{ | ||
"id": "base_top", | ||
"parent": "waist", | ||
"translation": { | ||
"x": 0, | ||
"y": 0, | ||
"z": 267 | ||
}, | ||
"geometry": { | ||
"r": 50, | ||
"l": 320, | ||
"translation": { | ||
"x": 0, | ||
"y": 0, | ||
"z": 160 | ||
} | ||
} | ||
}, | ||
{ | ||
"id": "upper_arm", | ||
"parent": "shoulder", | ||
"translation": { | ||
"x": 53.5, | ||
"y": 0, | ||
"z": 284.5 | ||
}, | ||
"geometry": { | ||
"x": 110, | ||
"y": 190, | ||
"z": 370, | ||
"translation": { | ||
"x": 0, | ||
"y": 0, | ||
"z": 135 | ||
} | ||
} | ||
}, | ||
{ | ||
"id": "upper_forearm", | ||
"parent": "elbow", | ||
"translation": { | ||
"x": 77.5, | ||
"y": 0, | ||
"z": -172.5 | ||
}, | ||
"geometry": { | ||
"x": 100, | ||
"y": 190, | ||
"z": 250, | ||
"translation": { | ||
"x": 49.49, | ||
"y": 0, | ||
"z": -49.49 | ||
}, | ||
"orientation": { | ||
"type": "ov_degrees", | ||
"value": { | ||
"x": 0.707106, | ||
"y": 0, | ||
"z": -0.707106, | ||
"th": 0 | ||
} | ||
} | ||
} | ||
}, | ||
{ | ||
"id": "lower_forearm", | ||
"parent": "forearm_rot", | ||
"translation": { | ||
"x": 0, | ||
"y": 0, | ||
"z": -170 | ||
}, | ||
"geometry": { | ||
"r": 45, | ||
"l": 285, | ||
"translation": { | ||
"x": 0, | ||
"y": -27.5, | ||
"z": -104.8 | ||
}, | ||
"orientation": { | ||
"type": "ov_degrees", | ||
"value": { | ||
"th": -90, | ||
"x": 0, | ||
"y": 0.2537568, | ||
"z": 0.9672615 | ||
} | ||
} | ||
} | ||
}, | ||
{ | ||
"id": "wrist_link", | ||
"parent": "wrist", | ||
"translation": { | ||
"x": 76, | ||
"y": 0, | ||
"z": -97 | ||
}, | ||
"geometry": { | ||
"x": 150, | ||
"y": 100, | ||
"z": 135, | ||
"translation": { | ||
"x": 75, | ||
"y": 10, | ||
"z": -67.5 | ||
} | ||
} | ||
}, | ||
{ | ||
"id": "gripper_mount", | ||
"parent": "gripper_rot", | ||
"translation": { | ||
"x": 0, | ||
"y": 0, | ||
"z": 0 | ||
}, | ||
"orientation": { | ||
"type": "ov_degrees", | ||
"value": { | ||
"x": 0, | ||
"y": 0, | ||
"z": -1, | ||
"th": 0 | ||
} | ||
} | ||
} | ||
], | ||
"joints": [ | ||
{ | ||
"id": "waist", | ||
"type": "revolute", | ||
"parent": "base", | ||
"axis": { | ||
"x": 0, | ||
"y": 0, | ||
"z": 1 | ||
}, | ||
"max": 359, | ||
"min": -359 | ||
}, | ||
{ | ||
"id": "shoulder", | ||
"type": "revolute", | ||
"parent": "base_top", | ||
"axis": { | ||
"x": 0, | ||
"y": 1, | ||
"z": 0 | ||
}, | ||
"max": 120, | ||
"min": -118 | ||
}, | ||
{ | ||
"id": "elbow", | ||
"type": "revolute", | ||
"parent": "upper_arm", | ||
"axis": { | ||
"x": 0, | ||
"y": 1, | ||
"z": 0 | ||
}, | ||
"max": 10, | ||
"min": -225 | ||
}, | ||
{ | ||
"id": "forearm_rot", | ||
"type": "revolute", | ||
"parent": "upper_forearm", | ||
"axis": { | ||
"x": 0, | ||
"y": 0, | ||
"z": -1 | ||
}, | ||
"max": 359, | ||
"min": -359 | ||
}, | ||
{ | ||
"id": "wrist", | ||
"type": "revolute", | ||
"parent": "lower_forearm", | ||
"axis": { | ||
"x": 0, | ||
"y": 1, | ||
"z": 0 | ||
}, | ||
"max": 179, | ||
"min": -97 | ||
}, | ||
{ | ||
"id": "gripper_rot", | ||
"type": "revolute", | ||
"parent": "wrist_link", | ||
"axis": { | ||
"x": 0, | ||
"y": 0, | ||
"z": -1 | ||
}, | ||
"max": 359, | ||
"min": -359 | ||
} | ||
] | ||
} |