arm/arm_model/机械臂URDF六坐标系不带夹爪/newURDF/urdf/newURDF.urdf

395 lines
8.4 KiB
XML

<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="newURDF">
<link
name="base_link">
<inertial>
<origin
xyz="0.097666 -1.0602 0.016983"
rpy="0 0 0" />
<mass
value="1.0623" />
<inertia
ixx="0.00202"
ixy="7.846E-08"
ixz="-1.6521E-08"
iyy="0.0031488"
iyz="-1.0021E-07"
izz="0.0051396" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="Link1">
<inertial>
<origin
xyz="0.0070301 -0.00030378 0.044333"
rpy="0 0 0" />
<mass
value="2.3117" />
<inertia
ixx="0.0035548"
ixy="1.4877E-06"
ixz="3.269E-05"
iyy="0.0024594"
iyz="1.066E-06"
izz="0.0036305" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link1.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link1.STL" />
</geometry>
</collision>
</link>
<joint
name="j1"
type="revolute">
<origin
xyz="0.18701 -1.0602 0.042134"
rpy="0 0 1.5708" />
<parent
link="base_link" />
<child
link="Link1" />
<axis
xyz="0 0 1" />
<limit
lower="-15.7"
upper="15.7"
effort="60"
velocity="3.14" />
</joint>
<link
name="Link2">
<inertial>
<origin
xyz="-9.2767E-06 -0.27664 0.019763"
rpy="0 0 0" />
<mass
value="0.9007" />
<inertia
ixx="0.0057226"
ixy="-1.0789E-05"
ixz="-6.9854E-13"
iyy="0.00032946"
iyz="-2.0483E-16"
izz="0.0060392" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link2.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link2.STL" />
</geometry>
</collision>
</link>
<joint
name="j2"
type="revolute">
<origin
xyz="-0.0208 0 0.085"
rpy="-1.5708 0 -1.5708" />
<parent
link="Link1" />
<child
link="Link2" />
<axis
xyz="0 0 1" />
<limit
lower="-1.57"
upper="1.57"
effort="60"
velocity="3.14" />
</joint>
<link
name="Link3">
<inertial>
<origin
xyz="0.0016734 -0.086963 -0.059109"
rpy="0 0 0" />
<mass
value="0.72964" />
<inertia
ixx="0.00040609"
ixy="-1.1866E-05"
ixz="8.3967E-07"
iyy="0.00028636"
iyz="4.7151E-08"
izz="0.00030158" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link3.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link3.STL" />
</geometry>
</collision>
</link>
<joint
name="j3"
type="revolute">
<origin
xyz="0 -0.404 0.0563"
rpy="0 0 -1.5708" />
<parent
link="Link2" />
<child
link="Link3" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="3"
effort="3"
velocity="3.14" />
</joint>
<link
name="Link4">
<inertial>
<origin
xyz="4.9724306803875E-05 -0.00207071321291896 0.143599808817138"
rpy="0 0 0" />
<mass
value="0.60214796640085" />
<inertia
ixx="0.000525809010016783"
ixy="1.23868002227642E-08"
ixz="-1.24134280805566E-08"
iyy="0.000546950540891618"
iyz="1.12515113310339E-06"
izz="0.000149799542930966" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link4.STL" />
</geometry>
<material
name="">
<color
rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link4.STL" />
</geometry>
</collision>
</link>
<joint
name="j4"
type="revolute">
<origin
xyz="0.047775 -0.0905 -0.0355"
rpy="-1.5708 0 -1.5708" />
<parent
link="Link3" />
<child
link="Link4" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="6.3"
effort="3"
velocity="3.14" />
</joint>
<link
name="Link5">
<inertial>
<origin
xyz="-1.00614222916379E-05 0.0581666861440572 -0.0240267717595721"
rpy="0 0 0" />
<mass
value="0.218165546730634" />
<inertia
ixx="8.12333089853061E-05"
ixy="1.14300936029607E-08"
ixz="-1.13719114058548E-08"
iyy="8.12745528093048E-05"
iyz="-5.01183167153332E-07"
izz="8.39758674297567E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link5.STL" />
</geometry>
<material
name="">
<color
rgba="0.898039215686275 0.917647058823529 0.929411764705882 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link5.STL" />
</geometry>
</collision>
</link>
<joint
name="j5"
type="revolute">
<origin
xyz="0 0.023 0.241"
rpy="1.5708 0 3.1416" />
<parent
link="Link4" />
<child
link="Link5" />
<axis
xyz="0 0 1" />
<limit
lower="-1.75"
upper="1.75"
effort="3"
velocity="3.14" />
</joint>
<link
name="Link6">
<inertial>
<origin
xyz="2.13317252848316E-05 0.000538972898537438 0.0999352955724812"
rpy="0 0 0" />
<mass
value="0.575128999928036" />
<inertia
ixx="0.00025728868876434"
ixy="-1.85839768859793E-06"
ixz="1.14575058864561E-07"
iyy="0.000169254451988166"
iyz="5.60715028730914E-08"
izz="0.000243919065707014" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link6.STL" />
</geometry>
<material
name="">
<color
rgba="0.749019607843137 0.749019607843137 0.749019607843137 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://newURDF/meshes/Link6.STL" />
</geometry>
</collision>
</link>
<joint
name="j6"
type="revolute">
<origin
xyz="1.4024E-05 0.1065 -0.022997"
rpy="1.5708 0 3.1416" />
<parent
link="Link5" />
<child
link="Link6" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="6.3"
effort="3"
velocity="3.14" />
</joint>
</robot>