| <?xml version="1.0"?> |
| <robot name="owl65"> |
|
|
| |
| <link name="base_link"> |
| <inertial> |
| <origin xyz="0 0 0" rpy="0 0 0"/> |
| <mass value="2.39"/> |
| <inertia ixx="0.0060063" ixy="0" ixz="0" iyy="0.0095451" iyz="0" izz="0.006006"/> |
| </inertial> |
| <visual> |
| <geometry> |
| <mesh filename="meshes/visual/owl_robot/base_link.stl"/> |
| </geometry> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="meshes/collision/owl_robot/base_link.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| |
| <link name="shoulder_link"> |
| <inertial> |
| <origin xyz="0 0 0" rpy="0 0 0"/> |
| <mass value="4.613"/> |
| <inertia ixx="0.0035279" ixy="0" ixz="0" iyy="0.0046955" iyz="0" izz="0.0048177"/> |
| </inertial> |
| <visual> |
| <geometry> |
| <mesh filename="meshes/visual/owl_robot/shoulder_link.stl"/> |
| </geometry> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="meshes/collision/owl_robot/shoulder_link.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="BJ" type="revolute"> |
| <origin xyz="0 0 0" rpy="-3.1416 0 0"/> |
| <parent link="base_link"/> |
| <child link="shoulder_link"/> |
| <axis xyz="0 0 1"/> |
| <limit lower="-3.14" upper="3.14" effort="500" velocity="50"/> |
| </joint> |
|
|
| |
| <link name="link1"> |
| <inertial> |
| <origin xyz="0 0 0" rpy="0 0 0"/> |
| <mass value="9.431"/> |
| <inertia ixx="0.0052455" ixy="0" ixz="0" iyy="0.028778" iyz="0" izz="0.032177"/> |
| </inertial> |
| <visual> |
| <geometry> |
| <mesh filename="meshes/visual/owl_robot/link1.stl"/> |
| </geometry> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="meshes/collision/owl_robot/link1.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="SJ" type="revolute"> |
| <origin xyz="0.00018339 0.066603 -0.1405" rpy="0.58944 1.5675 -0.983"/> |
| <parent link="shoulder_link"/> |
| <child link="link1"/> |
| <axis xyz="0.0027142 -0.0011243 1"/> |
| <limit lower="-1.6" upper="1.6" effort="500" velocity="50"/> |
| </joint> |
| |
| <link name="elbow_link"> |
| <inertial> |
| <origin xyz="0 0 0" rpy="0 0 0"/> |
| <mass value="4.613"/> |
| <inertia ixx="0.0023499" ixy="0" ixz="0" iyy="0.0030181" iyz="0" izz="0.0035661"/> |
| </inertial> |
| <visual> |
| <geometry> |
| <mesh filename="meshes/visual/owl_robot/elbow_link.stl"/> |
| </geometry> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="meshes/collision/owl_robot/elbow_link.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="EJ" type="revolute"> |
| <origin xyz="0.35575 0 -0.00096557" rpy="3.1389 -0.0018334 -1.5781"/> |
| <parent link="link1"/> |
| <child link="elbow_link"/> |
| <axis xyz="0 0 1"/> |
| <limit lower="-2.8" upper="3.14" effort="500" velocity="50"/> |
| </joint> |
|
|
| |
| <link name="link2"> |
| <inertial> |
| <origin xyz="0 0 0" rpy="0 0 0"/> |
| <mass value="2.4407"/> |
| <inertia ixx="0.009134" ixy="0" ixz="0" iyy="0.010823" iyz="0" izz="0.0041094"/> |
| </inertial> |
| <visual> |
| <geometry> |
| <mesh filename="meshes/visual/owl_robot/link2.stl"/> |
| </geometry> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="meshes/collision/owl_robot/link2.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="W1J" type="revolute"> |
| <origin xyz="0.00019567 -0.079361 -0.066603" rpy="1.5708 -0.0023608 0"/> |
| <parent link="elbow_link"/> |
| <child link="link2"/> |
| <axis xyz="0 0 -1"/> |
| <limit lower="-2.84489" upper="2.84489" effort="500" velocity="50"/> |
| </joint> |
|
|
| |
| <link name="w2w3_link"> |
| <inertial> |
| <origin xyz="0 0 0" rpy="0 0 0"/> |
| <mass value="3.118"/> |
| <inertia ixx="0.0014884" ixy="0" ixz="0" iyy="0.0016882" iyz="0" izz="0.0019291"/> |
| </inertial> |
| <visual> |
| <geometry> |
| <mesh filename="meshes/visual/owl_robot/w2w3_link.stl"/> |
| </geometry> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="meshes/collision/owl_robot/w2w3_link.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="W2J" type="revolute"> |
| <origin xyz="0 0 0.27639" rpy="2.745 -1.5667 -1.1726"/> |
| <parent link="link2"/> |
| <child link="w2w3_link"/> |
| <axis xyz="0.0037507 -0.00083382 0.99999"/> |
| <limit lower="-1.6" upper="0.78" effort="500" velocity="50"/> |
| </joint> |
| |
| <link name="end_effector_link"> |
| <inertial> |
| <origin xyz="0 0 0" rpy="0 0 0"/> |
| <mass value="0.188"/> |
| <inertia ixx="0.00017935" ixy="0" ixz="0" iyy="0.00017907" iyz="0" izz="0.00025742"/> |
| </inertial> |
| <visual> |
| <geometry> |
| <mesh filename="meshes/visual/owl_robot/end_effector_link.stl"/> |
| </geometry> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="meshes/collision/owl_robot/end_effector_link.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="W3J" type="revolute"> |
| <origin xyz="0 0 0" rpy="-1.2578 -1.5668 -0.31786"/> |
| <parent link="w2w3_link"/> |
| <child link="end_effector_link"/> |
| <axis xyz="0 0 1"/> |
| <limit lower="-3.1" upper="3.1" effort="500" velocity="50"/> |
| </joint> |
|
|
| |
| <link name="tcp"> |
| <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="tcp_frame" type="fixed"> |
| <origin xyz="4.33681e-19 0 0.1225" rpy="5.94633e-15 -1.33504e-14 -1.5708"/> |
| <parent link="end_effector_link"/> |
| <child link="tcp"/> |
| </joint> |
|
|
| </robot> |
|
|