Orangewood Labs OWL65 Integration
#22
by
skyequac
- opened
- .gitattributes +1 -0
- robots/owl65/config/owl65.yaml +11 -0
- robots/owl65/config/owl65_cfg.py +48 -0
- robots/owl65/urdf/meshes/collision/owl_robot/base_link.stl +3 -0
- robots/owl65/urdf/meshes/collision/owl_robot/elbow_link.stl +3 -0
- robots/owl65/urdf/meshes/collision/owl_robot/end_effector_link.stl +3 -0
- robots/owl65/urdf/meshes/collision/owl_robot/link1.stl +3 -0
- robots/owl65/urdf/meshes/collision/owl_robot/link2.stl +3 -0
- robots/owl65/urdf/meshes/collision/owl_robot/shoulder_link.stl +3 -0
- robots/owl65/urdf/meshes/collision/owl_robot/w2w3_link.stl +3 -0
- robots/owl65/urdf/meshes/visual/owl_robot/base_link.stl +3 -0
- robots/owl65/urdf/meshes/visual/owl_robot/elbow_link.stl +3 -0
- robots/owl65/urdf/meshes/visual/owl_robot/end_effector_link.stl +3 -0
- robots/owl65/urdf/meshes/visual/owl_robot/link1.stl +3 -0
- robots/owl65/urdf/meshes/visual/owl_robot/link2.stl +3 -0
- robots/owl65/urdf/meshes/visual/owl_robot/shoulder_link.stl +3 -0
- robots/owl65/urdf/meshes/visual/owl_robot/w2w3_link.stl +3 -0
- robots/owl65/urdf/owl65.urdf +198 -0
.gitattributes
CHANGED
@@ -80,3 +80,4 @@ saved_model/**/* filter=lfs diff=lfs merge=lfs -text
|
|
80 |
# Other binary files
|
81 |
*.pdf filter=lfs diff=lfs merge=lfs -text
|
82 |
*.PDF filter=lfs diff=lfs merge=lfs -text
|
|
|
|
80 |
# Other binary files
|
81 |
*.pdf filter=lfs diff=lfs merge=lfs -text
|
82 |
*.PDF filter=lfs diff=lfs merge=lfs -text
|
83 |
+
robots/owl65/urdf/meshes/collision/owl_robot/* filter=lfs diff=lfs merge=lfs -text
|
robots/owl65/config/owl65.yaml
ADDED
@@ -0,0 +1,11 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
1 |
+
kinematics:
|
2 |
+
urdf_path: "../urdf/owl65.urdf"
|
3 |
+
base_link: "base_link"
|
4 |
+
ee_link: "tcp"
|
5 |
+
collision_spheres_path: null
|
6 |
+
collision_spheres: null
|
7 |
+
self_collision_ignore:
|
8 |
+
- ["base_link", "link_1"]
|
9 |
+
- ["link_5", "link_6"]
|
10 |
+
robot_params:
|
11 |
+
robot_description_path: null
|
robots/owl65/config/owl65_cfg.py
ADDED
@@ -0,0 +1,48 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
1 |
+
from __future__ import annotations
|
2 |
+
from metasim.utils import configclass
|
3 |
+
from .base_robot_cfg import BaseActuatorCfg, BaseRobotCfg
|
4 |
+
|
5 |
+
|
6 |
+
@configclass
|
7 |
+
class Owl65Cfg(BaseRobotCfg):
|
8 |
+
name: str = "owl65"
|
9 |
+
num_joints: int = 6
|
10 |
+
urdf_path: str = "roboverse_data/robots/owl65/urdf/owl65.urdf"
|
11 |
+
base_link_name: str = "base_link" # Match the base link name in your URDF
|
12 |
+
enabled_gravity: bool = False
|
13 |
+
enabled_self_collisions: bool = True
|
14 |
+
dof_names: list[str] = ["BJ", "SJ", "EJ", "W1J", "W2J", "W3J"]
|
15 |
+
|
16 |
+
actuators: dict[str, BaseActuatorCfg] = {
|
17 |
+
"BJ": BaseActuatorCfg(velocity_limit=50),
|
18 |
+
"SJ": BaseActuatorCfg(velocity_limit=50),
|
19 |
+
"EJ": BaseActuatorCfg(velocity_limit=50),
|
20 |
+
"W1J": BaseActuatorCfg(velocity_limit=50),
|
21 |
+
"W2J": BaseActuatorCfg(velocity_limit=50),
|
22 |
+
"W3J": BaseActuatorCfg(velocity_limit=50),
|
23 |
+
}
|
24 |
+
|
25 |
+
joint_limits: dict[str, tuple[float, float]] = {
|
26 |
+
"BJ": (-3.14, 3.14),
|
27 |
+
"SJ": (-1.6, 1.6),
|
28 |
+
"EJ": (-2.8, 3.14),
|
29 |
+
"W1J": (-2.84489, 2.84489),
|
30 |
+
"W2J": (-1.6, 0.78),
|
31 |
+
"W3J": (-3.1, 3.1),
|
32 |
+
}
|
33 |
+
|
34 |
+
ee_body_name: str = "tcp"
|
35 |
+
|
36 |
+
# Initialize these as empty arrays if you don't have a gripper
|
37 |
+
gripper_open_q = []
|
38 |
+
gripper_close_q = []
|
39 |
+
|
40 |
+
# CuRobo configuration
|
41 |
+
curobo_ref_cfg_name: str = "owl65.yml"
|
42 |
+
curobo_tcp_rel_pos: tuple[float, float, float] = [0.0, 0.0, 0.1225]
|
43 |
+
curobo_tcp_rel_rot: tuple[float, float, float] = [0.0, 0.0, -1.5708]
|
44 |
+
|
45 |
+
# Add default values for any missing properties
|
46 |
+
default_ee_offset: tuple[float, float, float] = (0, 0, 0)
|
47 |
+
default_ee_orientation: tuple[float, float, float, float] = (1, 0, 0, 0)
|
48 |
+
|
robots/owl65/urdf/meshes/collision/owl_robot/base_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:fedee387adb87375d4db501ca012e7853b610d4610be563acd2dbe6220999332
|
3 |
+
size 648084
|
robots/owl65/urdf/meshes/collision/owl_robot/elbow_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:8a95f853ebe3d20e0d00c1bfc71f7efdd12bf971090d5cddd8f5c13b03396a26
|
3 |
+
size 872384
|
robots/owl65/urdf/meshes/collision/owl_robot/end_effector_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:5fc037b9696e659b61f90a98b5a0f0e053e4e6313956d0500b6e1771b159d25b
|
3 |
+
size 122984
|
robots/owl65/urdf/meshes/collision/owl_robot/link1.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:ac872c651380f01f675bd6816c7f67aa84705088c3ce0b8b0f5fb9b036e811e2
|
3 |
+
size 998284
|
robots/owl65/urdf/meshes/collision/owl_robot/link2.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:7bf7525c45fbc5f4e5843eb13e074af233f66dcd473051f36d7de190e992e3b3
|
3 |
+
size 2137784
|
robots/owl65/urdf/meshes/collision/owl_robot/shoulder_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:3d17976b9fd81a6c9617898b7ca3c059dc2ba9907bbeaa798ced60fcefbc74d5
|
3 |
+
size 937284
|
robots/owl65/urdf/meshes/collision/owl_robot/w2w3_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:71981e746ff004c1c67881a028c6453b46e1c61462fdf2218c01c0dee2de2e88
|
3 |
+
size 951384
|
robots/owl65/urdf/meshes/visual/owl_robot/base_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:fedee387adb87375d4db501ca012e7853b610d4610be563acd2dbe6220999332
|
3 |
+
size 648084
|
robots/owl65/urdf/meshes/visual/owl_robot/elbow_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:8a95f853ebe3d20e0d00c1bfc71f7efdd12bf971090d5cddd8f5c13b03396a26
|
3 |
+
size 872384
|
robots/owl65/urdf/meshes/visual/owl_robot/end_effector_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:5fc037b9696e659b61f90a98b5a0f0e053e4e6313956d0500b6e1771b159d25b
|
3 |
+
size 122984
|
robots/owl65/urdf/meshes/visual/owl_robot/link1.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:ac872c651380f01f675bd6816c7f67aa84705088c3ce0b8b0f5fb9b036e811e2
|
3 |
+
size 998284
|
robots/owl65/urdf/meshes/visual/owl_robot/link2.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:7bf7525c45fbc5f4e5843eb13e074af233f66dcd473051f36d7de190e992e3b3
|
3 |
+
size 2137784
|
robots/owl65/urdf/meshes/visual/owl_robot/shoulder_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:3d17976b9fd81a6c9617898b7ca3c059dc2ba9907bbeaa798ced60fcefbc74d5
|
3 |
+
size 937284
|
robots/owl65/urdf/meshes/visual/owl_robot/w2w3_link.stl
ADDED
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
1 |
+
version https://git-lfs.github.com/spec/v1
|
2 |
+
oid sha256:71981e746ff004c1c67881a028c6453b46e1c61462fdf2218c01c0dee2de2e88
|
3 |
+
size 951384
|
robots/owl65/urdf/owl65.urdf
ADDED
@@ -0,0 +1,198 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
1 |
+
<?xml version="1.0"?>
|
2 |
+
<robot name="owl65">
|
3 |
+
|
4 |
+
<!-- Base Link -->
|
5 |
+
<link name="base_link">
|
6 |
+
<inertial>
|
7 |
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
8 |
+
<mass value="2.39"/>
|
9 |
+
<inertia ixx="0.0060063" ixy="0" ixz="0" iyy="0.0095451" iyz="0" izz="0.006006"/>
|
10 |
+
</inertial>
|
11 |
+
<visual>
|
12 |
+
<geometry>
|
13 |
+
<mesh filename="meshes/visual/owl_robot/base_link.stl"/>
|
14 |
+
</geometry>
|
15 |
+
</visual>
|
16 |
+
<collision>
|
17 |
+
<geometry>
|
18 |
+
<mesh filename="meshes/collision/owl_robot/base_link.stl"/>
|
19 |
+
</geometry>
|
20 |
+
</collision>
|
21 |
+
</link>
|
22 |
+
|
23 |
+
<!-- Shoulder Link -->
|
24 |
+
<link name="shoulder_link">
|
25 |
+
<inertial>
|
26 |
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
27 |
+
<mass value="4.613"/>
|
28 |
+
<inertia ixx="0.0035279" ixy="0" ixz="0" iyy="0.0046955" iyz="0" izz="0.0048177"/>
|
29 |
+
</inertial>
|
30 |
+
<visual>
|
31 |
+
<geometry>
|
32 |
+
<mesh filename="meshes/visual/owl_robot/shoulder_link.stl"/>
|
33 |
+
</geometry>
|
34 |
+
</visual>
|
35 |
+
<collision>
|
36 |
+
<geometry>
|
37 |
+
<mesh filename="meshes/collision/owl_robot/shoulder_link.stl"/>
|
38 |
+
</geometry>
|
39 |
+
</collision>
|
40 |
+
</link>
|
41 |
+
|
42 |
+
<joint name="BJ" type="revolute">
|
43 |
+
<origin xyz="0 0 0" rpy="-3.1416 0 0"/>
|
44 |
+
<parent link="base_link"/>
|
45 |
+
<child link="shoulder_link"/>
|
46 |
+
<axis xyz="0 0 1"/>
|
47 |
+
<limit lower="-3.14" upper="3.14" effort="500" velocity="50"/>
|
48 |
+
</joint>
|
49 |
+
|
50 |
+
<!-- Link1 -->
|
51 |
+
<link name="link1">
|
52 |
+
<inertial>
|
53 |
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
54 |
+
<mass value="9.431"/>
|
55 |
+
<inertia ixx="0.0052455" ixy="0" ixz="0" iyy="0.028778" iyz="0" izz="0.032177"/>
|
56 |
+
</inertial>
|
57 |
+
<visual>
|
58 |
+
<geometry>
|
59 |
+
<mesh filename="meshes/visual/owl_robot/link1.stl"/>
|
60 |
+
</geometry>
|
61 |
+
</visual>
|
62 |
+
<collision>
|
63 |
+
<geometry>
|
64 |
+
<mesh filename="meshes/collision/owl_robot/link1.stl"/>
|
65 |
+
</geometry>
|
66 |
+
</collision>
|
67 |
+
</link>
|
68 |
+
|
69 |
+
<joint name="SJ" type="revolute">
|
70 |
+
<origin xyz="0.00018339 0.066603 -0.1405" rpy="0.58944 1.5675 -0.983"/>
|
71 |
+
<parent link="shoulder_link"/>
|
72 |
+
<child link="link1"/>
|
73 |
+
<axis xyz="0.0027142 -0.0011243 1"/>
|
74 |
+
<limit lower="-1.6" upper="1.6" effort="500" velocity="50"/>
|
75 |
+
</joint>
|
76 |
+
<!-- Elbow Link -->
|
77 |
+
<link name="elbow_link">
|
78 |
+
<inertial>
|
79 |
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
80 |
+
<mass value="4.613"/>
|
81 |
+
<inertia ixx="0.0023499" ixy="0" ixz="0" iyy="0.0030181" iyz="0" izz="0.0035661"/>
|
82 |
+
</inertial>
|
83 |
+
<visual>
|
84 |
+
<geometry>
|
85 |
+
<mesh filename="meshes/visual/owl_robot/elbow_link.stl"/>
|
86 |
+
</geometry>
|
87 |
+
</visual>
|
88 |
+
<collision>
|
89 |
+
<geometry>
|
90 |
+
<mesh filename="meshes/collision/owl_robot/elbow_link.stl"/>
|
91 |
+
</geometry>
|
92 |
+
</collision>
|
93 |
+
</link>
|
94 |
+
|
95 |
+
<joint name="EJ" type="revolute">
|
96 |
+
<origin xyz="0.35575 0 -0.00096557" rpy="3.1389 -0.0018334 -1.5781"/>
|
97 |
+
<parent link="link1"/>
|
98 |
+
<child link="elbow_link"/>
|
99 |
+
<axis xyz="0 0 1"/>
|
100 |
+
<limit lower="-2.8" upper="3.14" effort="500" velocity="50"/>
|
101 |
+
</joint>
|
102 |
+
|
103 |
+
<!-- Link2 -->
|
104 |
+
<link name="link2">
|
105 |
+
<inertial>
|
106 |
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
107 |
+
<mass value="2.4407"/>
|
108 |
+
<inertia ixx="0.009134" ixy="0" ixz="0" iyy="0.010823" iyz="0" izz="0.0041094"/>
|
109 |
+
</inertial>
|
110 |
+
<visual>
|
111 |
+
<geometry>
|
112 |
+
<mesh filename="meshes/visual/owl_robot/link2.stl"/>
|
113 |
+
</geometry>
|
114 |
+
</visual>
|
115 |
+
<collision>
|
116 |
+
<geometry>
|
117 |
+
<mesh filename="meshes/collision/owl_robot/link2.stl"/>
|
118 |
+
</geometry>
|
119 |
+
</collision>
|
120 |
+
</link>
|
121 |
+
|
122 |
+
<joint name="W1J" type="revolute">
|
123 |
+
<origin xyz="0.00019567 -0.079361 -0.066603" rpy="1.5708 -0.0023608 0"/>
|
124 |
+
<parent link="elbow_link"/>
|
125 |
+
<child link="link2"/>
|
126 |
+
<axis xyz="0 0 -1"/>
|
127 |
+
<limit lower="-2.84489" upper="2.84489" effort="500" velocity="50"/>
|
128 |
+
</joint>
|
129 |
+
|
130 |
+
<!-- W2W3 Link -->
|
131 |
+
<link name="w2w3_link">
|
132 |
+
<inertial>
|
133 |
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
134 |
+
<mass value="3.118"/>
|
135 |
+
<inertia ixx="0.0014884" ixy="0" ixz="0" iyy="0.0016882" iyz="0" izz="0.0019291"/>
|
136 |
+
</inertial>
|
137 |
+
<visual>
|
138 |
+
<geometry>
|
139 |
+
<mesh filename="meshes/visual/owl_robot/w2w3_link.stl"/>
|
140 |
+
</geometry>
|
141 |
+
</visual>
|
142 |
+
<collision>
|
143 |
+
<geometry>
|
144 |
+
<mesh filename="meshes/collision/owl_robot/w2w3_link.stl"/>
|
145 |
+
</geometry>
|
146 |
+
</collision>
|
147 |
+
</link>
|
148 |
+
|
149 |
+
<joint name="W2J" type="revolute">
|
150 |
+
<origin xyz="0 0 0.27639" rpy="2.745 -1.5667 -1.1726"/>
|
151 |
+
<parent link="link2"/>
|
152 |
+
<child link="w2w3_link"/>
|
153 |
+
<axis xyz="0.0037507 -0.00083382 0.99999"/>
|
154 |
+
<limit lower="-1.6" upper="0.78" effort="500" velocity="50"/>
|
155 |
+
</joint>
|
156 |
+
<!-- End Effector Link -->
|
157 |
+
<link name="end_effector_link">
|
158 |
+
<inertial>
|
159 |
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
160 |
+
<mass value="0.188"/>
|
161 |
+
<inertia ixx="0.00017935" ixy="0" ixz="0" iyy="0.00017907" iyz="0" izz="0.00025742"/>
|
162 |
+
</inertial>
|
163 |
+
<visual>
|
164 |
+
<geometry>
|
165 |
+
<mesh filename="meshes/visual/owl_robot/end_effector_link.stl"/>
|
166 |
+
</geometry>
|
167 |
+
</visual>
|
168 |
+
<collision>
|
169 |
+
<geometry>
|
170 |
+
<mesh filename="meshes/collision/owl_robot/end_effector_link.stl"/>
|
171 |
+
</geometry>
|
172 |
+
</collision>
|
173 |
+
</link>
|
174 |
+
|
175 |
+
<joint name="W3J" type="revolute">
|
176 |
+
<origin xyz="0 0 0" rpy="-1.2578 -1.5668 -0.31786"/>
|
177 |
+
<parent link="w2w3_link"/>
|
178 |
+
<child link="end_effector_link"/>
|
179 |
+
<axis xyz="0 0 1"/>
|
180 |
+
<limit lower="-3.1" upper="3.1" effort="500" velocity="50"/>
|
181 |
+
</joint>
|
182 |
+
|
183 |
+
<!-- TCP Link -->
|
184 |
+
<link name="tcp">
|
185 |
+
<inertial>
|
186 |
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
187 |
+
<mass value="1e-9"/>
|
188 |
+
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
189 |
+
</inertial>
|
190 |
+
</link>
|
191 |
+
|
192 |
+
<joint name="tcp_frame" type="fixed">
|
193 |
+
<origin xyz="4.33681e-19 0 0.1225" rpy="5.94633e-15 -1.33504e-14 -1.5708"/>
|
194 |
+
<parent link="end_effector_link"/>
|
195 |
+
<child link="tcp"/>
|
196 |
+
</joint>
|
197 |
+
|
198 |
+
</robot>
|