mirror of
https://github.com/huggingface/lerobot.git
synced 2026-05-21 03:30:10 +00:00
add urdfs
This commit is contained in:
+7
-1
@@ -116,7 +116,7 @@ packages = [
|
|||||||
[tool.ruff]
|
[tool.ruff]
|
||||||
line-length = 110
|
line-length = 110
|
||||||
target-version = "py310"
|
target-version = "py310"
|
||||||
exclude = ["tests/artifacts/**/*.safetensors", "*_pb2.py", "*_pb2_grpc.py"]
|
exclude = ["tests/artifacts/**/*.safetensors", "*_pb2.py", "*_pb2_grpc.py", "*.part", "*.stl"]
|
||||||
|
|
||||||
[tool.ruff.lint]
|
[tool.ruff.lint]
|
||||||
select = ["E4", "E7", "E9", "F", "I", "N", "B", "C4", "SIM"]
|
select = ["E4", "E7", "E9", "F", "I", "N", "B", "C4", "SIM"]
|
||||||
@@ -148,6 +148,12 @@ default.extend-ignore-identifiers-re = [
|
|||||||
"ein",
|
"ein",
|
||||||
]
|
]
|
||||||
|
|
||||||
|
[tool.typos.files]
|
||||||
|
extend-exclude = [
|
||||||
|
"*.stl",
|
||||||
|
"*.part",
|
||||||
|
]
|
||||||
|
|
||||||
[build-system]
|
[build-system]
|
||||||
requires = ["poetry-core"]
|
requires = ["poetry-core"]
|
||||||
build-backend = "poetry.core.masonry.api"
|
build-backend = "poetry.core.masonry.api"
|
||||||
|
|||||||
@@ -121,9 +121,7 @@ class SO101FollowerT(Robot):
|
|||||||
)
|
)
|
||||||
self.cameras = make_cameras_from_configs(config.cameras)
|
self.cameras = make_cameras_from_configs(config.cameras)
|
||||||
|
|
||||||
self.pin_robot = pin.RobotWrapper.BuildFromURDF(
|
self.pin_robot = pin.RobotWrapper.BuildFromURDF("urdf/so101_new_calib.urdf", "urdf")
|
||||||
"src/lerobot/SO101/so101_new_calib.urdf", "src/lerobot/SO101"
|
|
||||||
)
|
|
||||||
|
|
||||||
flip = {
|
flip = {
|
||||||
"shoulder_pan": True,
|
"shoulder_pan": True,
|
||||||
@@ -161,7 +159,6 @@ class SO101FollowerT(Robot):
|
|||||||
for motor in self.bus.motors:
|
for motor in self.bus.motors:
|
||||||
d[f"{motor}.pos"] = float
|
d[f"{motor}.pos"] = float
|
||||||
d[f"{motor}.vel"] = float
|
d[f"{motor}.vel"] = float
|
||||||
# d[f"{motor}.acc"] = float
|
|
||||||
d[f"{motor}.effort"] = float
|
d[f"{motor}.effort"] = float
|
||||||
return d
|
return d
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "84d8ae1881704ebae1ffb70a",
|
||||||
|
"documentMicroversion": "0eea3500852bdb2f58b1cb79",
|
||||||
|
"documentVersion": "a5c3b0dfaa52ddd6829011cd",
|
||||||
|
"elementId": "22efbe4e0bef24fcd20f96e5",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "MCOhripg0ry51VlsC",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Base_motor_holder_SO101 v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:8cd2f241037ea377af1191fffe0dd9d9006beea6dcc48543660ed41647072424
|
||||||
|
size 1877084
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "bf61a6bc85b1d1a8bf9ea51b",
|
||||||
|
"documentMicroversion": "20484d37162a32a8a41a37f2",
|
||||||
|
"documentVersion": "25801b070e5b360715de8a30",
|
||||||
|
"elementId": "312f32f0073fa6e8e36fba7a",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "MY69cJlqvSzIiODdH",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Base_SO101 v2 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:bb12b7026575e1f70ccc7240051f9d943553bf34e5128537de6cd86fae33924d
|
||||||
|
size 471584
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "652d5731024e57367badfda6",
|
||||||
|
"documentMicroversion": "56a8b8013480c176fd87df8d",
|
||||||
|
"documentVersion": "984ac31c92cac3664c8effb3",
|
||||||
|
"elementId": "6fb7b7f9315511b548d670ff",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "Mf4ZebMr4BkShucFj",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Motor_holder_SO101_Base v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:31242ae6fb59d8b15c66617b88ad8e9bded62d57c35d11c0c43a70d2f4caa95b
|
||||||
|
size 1129384
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "4bd66da73cacb4d946d43e44",
|
||||||
|
"documentMicroversion": "2bf56247e58b70e90806e318",
|
||||||
|
"documentVersion": "df78bb7089f1de7d5588d238",
|
||||||
|
"elementId": "d7dfe76e402c21bbd8124e43",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "MN9BZ1p69dQQtKTjq",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Motor_holder_SO101_Wrist v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:887f92e6013cb64ea3a1ab8675e92da1e0beacfd5e001f972523540545e08011
|
||||||
|
size 1052184
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "46218c02ef80d36172edbb35",
|
||||||
|
"documentMicroversion": "68b7d387e2500c451586ae59",
|
||||||
|
"documentVersion": "79c101d1a0207b77362b561a",
|
||||||
|
"elementId": "d4b1411d5d7333298f6e2458",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "MrHPLr9hZkrXwcSA4",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Moving_Jaw_SO101 v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:785a9dded2f474bc1d869e0d3dae398a3dcd9c0c345640040472210d2861fa9d
|
||||||
|
size 1413584
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "14078aa6723c502d07d6902e",
|
||||||
|
"documentMicroversion": "c0fca717407275159bcc6ed7",
|
||||||
|
"documentVersion": "3d9a887ff68fa477d98162b8",
|
||||||
|
"elementId": "43d24b3857ff686b275578bf",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "MrQ6Kmk9QDZlwbp95",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Rotation_Pitch_SO101 v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:9be900cc2a2bf718102841ef82ef8d2873842427648092c8ed2ca1e2ef4ffa34
|
||||||
|
size 883684
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "56e5f3702dad85e17841d2e2",
|
||||||
|
"documentMicroversion": "7958a6acbc8e0d0a0a611746",
|
||||||
|
"documentVersion": "29a4c51b8bf277a22743a333",
|
||||||
|
"elementId": "8c14fb13a6557ec89ff5d227",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "MOcaIFg8XgL+Ybg9z",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "STS3215_03a_no_horn v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:75ef3781b752e4065891aea855e34dc161a38a549549cd0970cedd07eae6f887
|
||||||
|
size 865884
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "d2941bdba816affebdc6d6f0",
|
||||||
|
"documentMicroversion": "5904ef3cea04a0d0bc88b698",
|
||||||
|
"documentVersion": "dd4f7470101215836a4ae8c9",
|
||||||
|
"elementId": "e670b72d49b06f88fad5dbd8",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "M5vQNpe0onRFueych",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "STS3215_03a v1 <5>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:a37c871fb502483ab96c256baf457d36f2e97afc9205313d9c5ab275ef941cd0
|
||||||
|
size 954084
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "9f5d6db47eb112442b9f130f",
|
||||||
|
"documentMicroversion": "e99cf45162e34789bd99512b",
|
||||||
|
"documentVersion": "817ebf29c5663d412edc0753",
|
||||||
|
"elementId": "2813aaffe3c8a342616d3527",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "M9yAEiX02J3c4HqXa",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Under_arm_SO101 v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:d01d1f2de365651dcad9d6669e94ff87ff7652b5bb2d10752a66a456a86dbc71
|
||||||
|
size 1975884
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "57f3eae43434311c28ac752b",
|
||||||
|
"documentMicroversion": "33eeab136e831427f0f0ca74",
|
||||||
|
"documentVersion": "435d47b71ef26075bf82672c",
|
||||||
|
"elementId": "a8e0c02dc43f7ccb373c52e4",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "Ml3rwO4kV53jDRgcs",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Upper_arm_SO101 v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:475056e03a17e71919b82fd88ab9a0b898ab50164f2a7943652a6b2941bb2d4f
|
||||||
|
size 1303484
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "066f8b5064455ec46759cd8c",
|
||||||
|
"documentMicroversion": "04c5790374bf3edfbbb7e818",
|
||||||
|
"documentVersion": "408440a116f7d8700bbb11c2",
|
||||||
|
"elementId": "dc35e56269e36de39738b34d",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "MjhXxhyF1+iAgCtUh",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "WaveShare_Mounting_Plate_SO101 v2 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:e197e24005a07d01bbc06a8c42311664eaeda415bf859f68fa247884d0f1a6e9
|
||||||
|
size 62784
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "e02f1e1d3fdd766a19a55890",
|
||||||
|
"documentMicroversion": "03f1dfc090db6bbecdb14475",
|
||||||
|
"documentVersion": "8a15327cfbde0344e0951076",
|
||||||
|
"elementId": "2317bd70c68862eeebd64492",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "MpI0voU28BOAZ6D9x",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Wrist_Roll_Follower_SO101 v1 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:4b17b410a12d64ec39554abc3e8054d8a97384b2dc4a8d95a5ecb2a93670f5f4
|
||||||
|
size 1439884
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"configuration": "default",
|
||||||
|
"documentId": "eb144d215e733b8dbbb50b81",
|
||||||
|
"documentMicroversion": "4fef760722dee3a9b5ff19b1",
|
||||||
|
"documentVersion": "5880c1e9413206cac10772d0",
|
||||||
|
"elementId": "3c22c2c23cb0ce545b9df2ba",
|
||||||
|
"fullConfiguration": "default",
|
||||||
|
"id": "Ma99J59HxnSe2TArb",
|
||||||
|
"isStandardContent": false,
|
||||||
|
"name": "Wrist_Roll_Pitch_SO101 v2 <1>",
|
||||||
|
"partId": "JFD",
|
||||||
|
"suppressed": false,
|
||||||
|
"type": "Part"
|
||||||
|
}
|
||||||
@@ -0,0 +1,3 @@
|
|||||||
|
version https://git-lfs.github.com/spec/v1
|
||||||
|
oid sha256:6c7ec5525b4d8b9e397a30ab4bb0037156a5d5f38a4adf2c7d943d6c56eda5ae
|
||||||
|
size 2699784
|
||||||
@@ -0,0 +1,453 @@
|
|||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<!-- Generated using onshape-to-robot -->
|
||||||
|
<!-- Onshape https://cad.onshape.com/documents/7715cc284bb430fe6dab4ffd/w/4fd0791b683777b02f8d975a/e/826c553ede3b7592eb9ca800 -->
|
||||||
|
<robot name="so101_new_calib">
|
||||||
|
|
||||||
|
<!-- Materials -->
|
||||||
|
<material name="3d_printed">
|
||||||
|
<color rgba="1.0 0.82 0.12 1.0"/>
|
||||||
|
</material>
|
||||||
|
<material name="sts3215">
|
||||||
|
<color rgba="0.1 0.1 0.1 1.0"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<!-- Link base -->
|
||||||
|
<link name="base_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.0137179 -5.19711e-05 0.0334843" rpy="0 0 0"/>
|
||||||
|
<mass value="0.147"/>
|
||||||
|
<inertia ixx="0.000114686" ixy="-4.59787e-07" ixz="4.97151e-06" iyy="0.000136117" iyz="9.75275e-08" izz="0.000130364"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part base_motor_holder_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.00636471 -9.94414e-05 -0.0024" rpy="1.5708 -1.67685e-15 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/base_motor_holder_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.00636471 -9.94414e-05 -0.0024" rpy="1.5708 -1.67685e-15 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/base_motor_holder_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part base_so101_v2 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.00636471 -8.97657e-09 -0.0024" rpy="1.5708 -2.78073e-29 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/base_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.00636471 -8.97657e-09 -0.0024" rpy="1.5708 -2.78073e-29 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/base_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part sts3215_03a_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0263353 -8.97657e-09 0.0437" rpy="-8.21148e-16 7.84513e-18 1.249e-15"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0263353 -8.97657e-09 0.0437" rpy="-8.21148e-16 7.84513e-18 1.249e-15"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part waveshare_mounting_plate_so101_v2 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0309827 -0.000199441 0.0474" rpy="1.5708 -1.35493e-14 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/waveshare_mounting_plate_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0309827 -0.000199441 0.0474" rpy="1.5708 -1.35493e-14 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/waveshare_mounting_plate_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link shoulder -->
|
||||||
|
<link name="shoulder_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.0307604 -1.66727e-05 -0.0252713" rpy="0 0 0"/>
|
||||||
|
<mass value="0.100006"/>
|
||||||
|
<inertia ixx="8.3759e-05" ixy="7.55525e-08" ixz="-1.16342e-06" iyy="8.10403e-05" iyz="1.54663e-07" izz="2.39783e-05"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part sts3215_03a_v1_2 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0303992 0.000422241 -0.0417" rpy="1.5708 1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0303992 0.000422241 -0.0417" rpy="1.5708 1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part motor_holder_so101_base_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0675992 -0.000177759 0.0158499" rpy="1.5708 -1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/motor_holder_so101_base_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0675992 -0.000177759 0.0158499" rpy="1.5708 -1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/motor_holder_so101_base_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part rotation_pitch_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0122008 2.22413e-05 0.0464" rpy="-1.5708 2.35221e-33 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/rotation_pitch_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0122008 2.22413e-05 0.0464" rpy="-1.5708 2.35221e-33 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/rotation_pitch_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link upper_arm -->
|
||||||
|
<link name="upper_arm_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.0898471 -0.00838224 0.0184089" rpy="0 0 0"/>
|
||||||
|
<mass value="0.103"/>
|
||||||
|
<inertia ixx="4.08002e-05" ixy="-1.97819e-05" ixz="-4.03016e-08" iyy="0.000147318" iyz="8.97326e-09" izz="0.000142487"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part sts3215_03a_v1_3 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.11257 -0.0155 0.0187" rpy="-3.14159 -5.27356e-16 -1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.11257 -0.0155 0.0187" rpy="-3.14159 -5.27356e-16 -1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part upper_arm_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.065085 0.012 0.0182" rpy="3.14159 -0 -1.30911e-30"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/upper_arm_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.065085 0.012 0.0182" rpy="3.14159 -0 -1.30911e-30"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/upper_arm_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link lower_arm -->
|
||||||
|
<link name="lower_arm_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.0980701 0.00324376 0.0182831" rpy="0 0 0"/>
|
||||||
|
<mass value="0.104"/>
|
||||||
|
<inertia ixx="2.87438e-05" ixy="7.41152e-06" ixz="1.26409e-06" iyy="0.000159844" iyz="-4.90188e-08" izz="0.00014529"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part under_arm_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0648499 -0.032 0.0182" rpy="3.14159 -0 6.67202e-31"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/under_arm_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0648499 -0.032 0.0182" rpy="3.14159 -0 6.67202e-31"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/under_arm_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part motor_holder_so101_wrist_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0648499 -0.032 0.018" rpy="-3.14159 -2.55351e-15 -1.83387e-30"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/motor_holder_so101_wrist_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0648499 -0.032 0.018" rpy="-3.14159 -2.55351e-15 -1.83387e-30"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/motor_holder_so101_wrist_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part sts3215_03a_v1_4 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.1224 0.0052 0.0187" rpy="-3.14159 -7.88861e-31 -3.14159"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.1224 0.0052 0.0187" rpy="-3.14159 -7.88861e-31 -3.14159"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link wrist -->
|
||||||
|
<link name="wrist_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000103312 -0.0386143 0.0281156" rpy="0 0 0"/>
|
||||||
|
<mass value="0.079"/>
|
||||||
|
<inertia ixx="3.68263e-05" ixy="1.7893e-08" ixz="-5.28128e-08" iyy="2.5391e-05" iyz="3.6412e-06" izz="2.1e-05"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part sts3215_03a_no_horn_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="8.32667e-17 -0.0424 0.0306" rpy="1.5708 1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_no_horn_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="8.32667e-17 -0.0424 0.0306" rpy="1.5708 1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_no_horn_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part wrist_roll_pitch_so101_v2 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 -0.028 0.0181" rpy="-1.5708 -1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/wrist_roll_pitch_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 -0.028 0.0181" rpy="-1.5708 -1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/wrist_roll_pitch_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link gripper -->
|
||||||
|
<link name="gripper_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.000213627 0.000245138 -0.025187" rpy="0 0 0"/>
|
||||||
|
<mass value="0.087"/>
|
||||||
|
<inertia ixx="2.75087e-05" ixy="-3.35241e-07" ixz="-5.7352e-06" iyy="4.33657e-05" iyz="-5.17847e-08" izz="3.45059e-05"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part sts3215_03a_v1_5 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0077 0.0001 -0.0234" rpy="-1.5708 -5.19179e-17 -1.66533e-16"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0077 0.0001 -0.0234" rpy="-1.5708 -5.19179e-17 -1.66533e-16"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part wrist_roll_follower_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="8.32667e-17 -0.000218214 0.000949706" rpy="-3.14159 -5.55112e-17 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/wrist_roll_follower_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="8.32667e-17 -0.000218214 0.000949706" rpy="-3.14159 -5.55112e-17 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/wrist_roll_follower_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Gripper frame (dummy link + fixed joint) -->
|
||||||
|
<link name="gripper_frame_link">
|
||||||
|
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="1e-9"/>
|
||||||
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="gripper_frame_joint" type="fixed">
|
||||||
|
<origin xyz="-0.0079 -0.000218121 -0.0981274" rpy="0 3.14159 0"/>
|
||||||
|
<parent link="gripper_link"/>
|
||||||
|
<child link="gripper_frame_link"/>
|
||||||
|
<axis xyz="0 0 0"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Link moving_jaw_so101_v1 -->
|
||||||
|
<link name="moving_jaw_so101_v1_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.00157495 -0.0300244 0.0192755" rpy="0 0 0"/>
|
||||||
|
<mass value="0.012"/>
|
||||||
|
<inertia ixx="6.61427e-06" ixy="-3.19807e-07" ixz="-5.90717e-09" iyy="1.89032e-06" iyz="-1.09945e-07" izz="5.28738e-06"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part moving_jaw_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-5.55112e-17 -5.55112e-17 0.0189" rpy="9.53145e-17 6.93889e-18 1.24077e-24"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/moving_jaw_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-5.55112e-17 -5.55112e-17 0.0189" rpy="9.53145e-17 6.93889e-18 1.24077e-24"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/moving_jaw_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Joint from gripper to moving_jaw_so101_v1 -->
|
||||||
|
<joint name="gripper" type="revolute">
|
||||||
|
<origin xyz="0.0202 0.0188 -0.0234" rpy="1.5708 -5.24284e-08 -1.41553e-15"/>
|
||||||
|
<parent link="gripper_link"/>
|
||||||
|
<child link="moving_jaw_so101_v1_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-0.174533" upper="1.74533"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="gripper_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="gripper">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor6">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from wrist to gripper -->
|
||||||
|
<joint name="wrist_roll" type="revolute">
|
||||||
|
<origin xyz="5.55112e-17 -0.0611 0.0181" rpy="1.5708 0.0486795 3.14159"/>
|
||||||
|
<parent link="wrist_link"/>
|
||||||
|
<child link="gripper_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-2.74385" upper="2.84121"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="wrist_roll_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="wrist_roll">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor5">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from lower_arm to wrist -->
|
||||||
|
<joint name="wrist_flex" type="revolute">
|
||||||
|
<origin xyz="-0.1349 0.0052 3.62355e-17" rpy="4.02456e-15 8.67362e-16 -1.5708"/>
|
||||||
|
<parent link="lower_arm_link"/>
|
||||||
|
<child link="wrist_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-1.65806" upper="1.65806"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="wrist_flex_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="wrist_flex">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor4">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from upper_arm to lower_arm -->
|
||||||
|
<!-- Note: 5-degree calibration offset applied to joint limits -->
|
||||||
|
<joint name="elbow_flex" type="revolute">
|
||||||
|
<origin xyz="-0.11257 -0.028 1.73763e-16" rpy="-3.63608e-16 8.74301e-16 1.5708"/>
|
||||||
|
<parent link="upper_arm_link"/>
|
||||||
|
<child link="lower_arm_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-1.69" upper="1.69"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="elbow_flex_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="elbow_flex">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor3">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from shoulder to upper_arm -->
|
||||||
|
<joint name="shoulder_lift" type="revolute">
|
||||||
|
<origin xyz="-0.0303992 -0.0182778 -0.0542" rpy="-1.5708 -1.5708 0"/>
|
||||||
|
<parent link="shoulder_link"/>
|
||||||
|
<child link="upper_arm_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-1.74533" upper="1.74533"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="shoulder_lift_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="shoulder_lift">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor2">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from base to shoulder -->
|
||||||
|
<joint name="shoulder_pan" type="revolute">
|
||||||
|
<origin xyz="0.0388353 -8.97657e-09 0.0624" rpy="3.14159 4.18253e-17 -3.14159"/>
|
||||||
|
<parent link="base_link"/>
|
||||||
|
<child link="shoulder_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-1.91986" upper="1.91986"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="shoulder_pan_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="shoulder_pan">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor1">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
</robot>
|
||||||
@@ -0,0 +1,435 @@
|
|||||||
|
<?xml version='1.0' encoding='utf-8'?>
|
||||||
|
<!-- Generated using onshape-to-robot -->
|
||||||
|
<!-- Onshape https://cad.onshape.com/documents/7715cc284bb430fe6dab4ffd/w/4fd0791b683777b02f8d975a/e/826c553ede3b7592eb9ca800 -->
|
||||||
|
<robot name="so101_old_calib">
|
||||||
|
|
||||||
|
<!-- Materials -->
|
||||||
|
<material name="3d_printed">
|
||||||
|
<color rgba="1.0 0.82 0.12 1.0"/>
|
||||||
|
</material>
|
||||||
|
<material name="sts3215">
|
||||||
|
<color rgba="0.1 0.1 0.1 1.0"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<!-- Link base -->
|
||||||
|
<link name="base">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.020739 0.00204287 0.065966" rpy="0 0 0"/>
|
||||||
|
<mass value="0.147"/>
|
||||||
|
<inertia ixx="0.000136117" ixy="4.59787e-07" ixz="9.75275e-08" iyy="0.000114686" iyz="-4.97151e-06" izz="0.000130364"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part base_motor_holder_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0206915 0.0221255 0.0300817" rpy="1.5708 -1.23909e-16 2.33147e-15"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/base_motor_holder_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0206915 0.0221255 0.0300817" rpy="1.5708 -1.23909e-16 2.33147e-15"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/base_motor_holder_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part base_so101_v2 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0207909 0.0221255 0.0300817" rpy="1.5708 -0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/base_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0207909 0.0221255 0.0300817" rpy="1.5708 -0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/base_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part sts3215_03a_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0207909 -0.0105745 0.0761817" rpy="-2.20282e-15 2.77556e-17 -1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0207909 -0.0105745 0.0761817" rpy="-2.20282e-15 2.77556e-17 -1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part waveshare_mounting_plate_so101_v2 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0205915 0.0467435 0.0798817" rpy="1.5708 -1.21716e-14 2.33147e-15"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/waveshare_mounting_plate_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0205915 0.0467435 0.0798817" rpy="1.5708 -1.21716e-14 2.33147e-15"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/waveshare_mounting_plate_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link shoulder -->
|
||||||
|
<link name="shoulder">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.0307604 -1.66727e-05 -0.0252713" rpy="0 0 0"/>
|
||||||
|
<mass value="0.100006"/>
|
||||||
|
<inertia ixx="8.3759e-05" ixy="7.55525e-08" ixz="-1.16342e-06" iyy="8.10403e-05" iyz="1.54663e-07" izz="2.39783e-05"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part sts3215_03a_v1_2 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0303992 0.000422241 -0.0417" rpy="1.5708 1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0303992 0.000422241 -0.0417" rpy="1.5708 1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part motor_holder_so101_base_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0675992 -0.000177759 0.0158499" rpy="1.5708 -1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/motor_holder_so101_base_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0675992 -0.000177759 0.0158499" rpy="1.5708 -1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/motor_holder_so101_base_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part rotation_pitch_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0122008 2.22413e-05 0.0464" rpy="-1.5708 -0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/rotation_pitch_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0122008 2.22413e-05 0.0464" rpy="-1.5708 -0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/rotation_pitch_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link upper_arm -->
|
||||||
|
<link name="upper_arm">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.00838224 0.0898471 0.0184089" rpy="0 0 0"/>
|
||||||
|
<mass value="0.103"/>
|
||||||
|
<inertia ixx="0.000147318" ixy="1.97819e-05" ixz="8.97326e-09" iyy="4.08002e-05" iyz="4.03016e-08" izz="0.000142487"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part sts3215_03a_v1_3 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0155 0.11257 0.0187" rpy="-3.14159 -3.22659e-15 -3.14159"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0155 0.11257 0.0187" rpy="-3.14159 -3.22659e-15 -3.14159"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part upper_arm_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.012 0.065085 0.0182" rpy="3.14159 -1.22125e-15 -1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/upper_arm_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.012 0.065085 0.0182" rpy="3.14159 -1.22125e-15 -1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/upper_arm_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link lower_arm -->
|
||||||
|
<link name="lower_arm">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.00324376 -0.0980701 0.0182831" rpy="0 0 0"/>
|
||||||
|
<mass value="0.104"/>
|
||||||
|
<inertia ixx="0.000159844" ixy="-7.41152e-06" ixz="4.90188e-08" iyy="2.87438e-05" iyz="1.26409e-06" izz="0.00014529"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part under_arm_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.032 -0.0648499 0.0182" rpy="3.14159 -1.11022e-16 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/under_arm_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.032 -0.0648499 0.0182" rpy="3.14159 -1.11022e-16 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/under_arm_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part motor_holder_so101_wrist_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.032 -0.0648499 0.018" rpy="-3.14159 -1.11022e-16 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/motor_holder_so101_wrist_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.032 -0.0648499 0.018" rpy="-3.14159 -1.11022e-16 1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/motor_holder_so101_wrist_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part sts3215_03a_v1_4 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-0.0052 -0.1224 0.0187" rpy="3.14159 -8.24341e-15 -1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.0052 -0.1224 0.0187" rpy="3.14159 -8.24341e-15 -1.5708"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link wrist -->
|
||||||
|
<link name="wrist">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000103312 -0.0386143 0.0281156" rpy="0 0 0"/>
|
||||||
|
<mass value="0.079"/>
|
||||||
|
<inertia ixx="3.68263e-05" ixy="1.7893e-08" ixz="-5.28128e-08" iyy="2.5391e-05" iyz="3.6412e-06" izz="2.1e-05"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part sts3215_03a_no_horn_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 -0.0424 0.0306" rpy="1.5708 1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_no_horn_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 -0.0424 0.0306" rpy="1.5708 1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_no_horn_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part wrist_roll_pitch_so101_v2 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="-2.77556e-17 -0.028 0.0181" rpy="-1.5708 -1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/wrist_roll_pitch_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-2.77556e-17 -0.028 0.0181" rpy="-1.5708 -1.5708 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/wrist_roll_pitch_so101_v2.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link gripper -->
|
||||||
|
<link name="gripper">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.000213627 0.000245138 -0.025187" rpy="0 0 0"/>
|
||||||
|
<mass value="0.087"/>
|
||||||
|
<inertia ixx="2.75087e-05" ixy="-3.35241e-07" ixz="-5.7352e-06" iyy="4.33657e-05" iyz="-5.17847e-08" izz="3.45059e-05"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part sts3215_03a_v1_5 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0077 0.0001 -0.0234" rpy="-1.5708 -5.55112e-17 -1.38213e-14"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="sts3215"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0077 0.0001 -0.0234" rpy="-1.5708 -5.55112e-17 -1.38213e-14"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/sts3215_03a_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<!-- Part wrist_roll_follower_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="1.11022e-16 -0.000218214 0.000949706" rpy="-3.14159 -5.55112e-17 -6.22813e-24"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/wrist_roll_follower_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="1.11022e-16 -0.000218214 0.000949706" rpy="-3.14159 -5.55112e-17 -6.22813e-24"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/wrist_roll_follower_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Link jaw -->
|
||||||
|
<link name="jaw">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.00157495 -0.0300244 0.0192755" rpy="0 0 0"/>
|
||||||
|
<mass value="0.012"/>
|
||||||
|
<inertia ixx="6.61427e-06" ixy="-3.19807e-07" ixz="-5.90717e-09" iyy="1.89032e-06" iyz="-1.09945e-07" izz="5.28738e-06"/>
|
||||||
|
</inertial>
|
||||||
|
<!-- Part moving_jaw_so101_v1 -->
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 1.89351e-17 0.0189" rpy="9.53145e-17 -1.20743e-23 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/moving_jaw_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="3d_printed"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 1.89351e-17 0.0189" rpy="9.53145e-17 -1.20743e-23 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="assets/moving_jaw_so101_v1.stl"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Joint from gripper to jaw -->
|
||||||
|
<joint name="gripper" type="revolute">
|
||||||
|
<origin xyz="0.0202 0.0188 -0.0234" rpy="1.5708 -7.91661e-17 -1.0396e-16"/>
|
||||||
|
<parent link="gripper"/>
|
||||||
|
<child link="jaw"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-0.174533" upper="1.74533"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="gripper_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="gripper">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor6">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from wrist to gripper -->
|
||||||
|
<joint name="wrist_roll" type="revolute">
|
||||||
|
<origin xyz="2.77556e-17 -0.0611 0.0181" rpy="1.5708 -9.38083e-08 3.14159"/>
|
||||||
|
<parent link="wrist"/>
|
||||||
|
<child link="gripper"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-2.79253" upper="2.79253"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="wrist_roll_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="wrist_roll">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor5">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from lower_arm to wrist -->
|
||||||
|
<joint name="wrist_flex" type="revolute">
|
||||||
|
<origin xyz="-0.0052 -0.1349 3.40439e-16" rpy="-1.41553e-15 4.91611e-15 7.56157e-09"/>
|
||||||
|
<parent link="lower_arm"/>
|
||||||
|
<child link="wrist"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-1.65806" upper="1.65806"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="wrist_flex_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="wrist_flex">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor4">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from upper_arm to lower_arm -->
|
||||||
|
<joint name="elbow_flex" type="revolute">
|
||||||
|
<origin xyz="-0.028 0.11257 1.24466e-16" rpy="1.89432e-15 -3.22659e-15 -3.14159"/>
|
||||||
|
<parent link="upper_arm"/>
|
||||||
|
<child link="lower_arm"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-0.174533" upper="3.14159"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="elbow_flex_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="elbow_flex">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor3">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from shoulder to upper_arm -->
|
||||||
|
<joint name="shoulder_lift" type="revolute">
|
||||||
|
<origin xyz="-0.0303992 -0.0182778 -0.0542" rpy="-1.5708 1.5708 0"/>
|
||||||
|
<parent link="shoulder"/>
|
||||||
|
<child link="upper_arm"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-3.31613" upper="0.174533"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="shoulder_lift_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="shoulder_lift">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor2">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<!-- Joint from base to shoulder -->
|
||||||
|
<joint name="shoulder_pan" type="revolute">
|
||||||
|
<origin xyz="0.0207909 -0.0230745 0.0948817" rpy="-3.14159 6.03684e-16 1.5708"/>
|
||||||
|
<parent link="base"/>
|
||||||
|
<child link="shoulder"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit effort="10" velocity="10" lower="-1.91986" upper="1.91986"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<transmission name="shoulder_pan_trans">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="shoulder_pan">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="motor1">
|
||||||
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
</robot>
|
||||||
Reference in New Issue
Block a user