123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442 |
- <?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="mr12urdf20240605">
- <link
- name="base_link">
- <!-- <inertial>
- <origin
- xyz="-0.0389794721428083 3.18209550907445E-05 0.114464775769165"
- rpy="0 0 0" />
- <mass
- value="27.8470958329326" />
- <inertia
- ixx="0.333719655951858"
- ixy="-0.000162752951771119"
- ixz="-0.0150515703369821"
- iyy="0.572256719027697"
- iyz="6.64144679179418E-05"
- izz="0.74716855955823" />
- </inertial> -->
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/base_link.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="0 1 1 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/base_link.STL" />
- </geometry>
- </collision>
- </link>
- <link
- name="Link1">
- <inertial>
- <origin
- xyz="0.0015836 0.02481 -0.16429"
- rpy="0 0 0" />
- <mass
- value="28.856" />
- <inertia
- ixx="0.80293"
- ixy="0.2052"
- ixz="-0.085925"
- iyy="0.84748"
- iyz="-0.048338"
- izz="0.87668" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link1.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="1 1 1 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link1.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint1"
- type="revolute">
- <origin
- xyz="0 0 0.55"
- rpy="0 0 0" />
- <parent
- link="base_link" />
- <child
- link="Link1" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-2.878"
- upper="2.878"
- effort="150"
- velocity="3.541" />
- </joint>
- <link
- name="Link2">
- <inertial>
- <origin
- xyz="0.318649688799688 -0.000235571433145232 0.186136694407231"
- rpy="0 0 0" />
- <mass
- value="7.80684304255034" />
- <inertia
- ixx="0.0281236828911867"
- ixy="0.000281518665603689"
- ixz="-0.00939923269411962"
- iyy="0.185870193003645"
- iyz="1.16807601383937E-05"
- izz="0.200135929390865" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link2.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="1 1 1 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link2.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint2"
- type="revolute">
- <origin
- xyz="0.14974 0.035343 0"
- rpy="1.5708 -1.5708 0" />
- <parent
- link="Link1" />
- <child
- link="Link2" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-2.529"
- upper="1.396"
- effort="150"
- velocity="3.541" />
- </joint>
- <link
- name="Link3">
- <inertial>
- <origin
- xyz="0.108553296371736 -0.0970725190395638 0.00155584136936515"
- rpy="0 0 0" />
- <mass
- value="13.1020677700115" />
- <inertia
- ixx="0.0894771695987357"
- ixy="0.00373169975921231"
- ixz="0.00305911419576535"
- iyy="0.0755527499176048"
- iyz="0.00497831742143842"
- izz="0.0627128517779011" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link3.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="1 1 1 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link3.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint3"
- type="revolute">
- <origin
- xyz="0.76075 0 0.033754"
- rpy="0 0 0" />
- <parent
- link="Link2" />
- <child
- link="Link3" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-1.308"
- upper="2.529"
- effort="150"
- velocity="3.733" />
- </joint>
- <link
- name="Link4">
- <inertial>
- <origin
- xyz="0.0144892098854688 -0.000636132360795127 -0.376459479520837"
- rpy="0 0 0" />
- <mass
- value="8.67998704574409" />
- <inertia
- ixx="0.466226625992446"
- ixy="0.000500906822306766"
- ixz="-0.015294045664646"
- iyy="0.451075373457536"
- iyz="0.000649456671583942"
- izz="0.036563182959402" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link4.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="0 1 1 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link4.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint4"
- type="revolute">
- <origin
- xyz="0.19783 -1.0829 0"
- rpy="1.5708 0 0" />
- <parent
- link="Link3" />
- <child
- link="Link4" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-1.6"
- upper="1.6"
- effort="88.5"
- velocity="6.838" />
- </joint>
- <link
- name="Link5">
- <inertial>
- <origin
- xyz="-6.1697E-06 -0.048434 -0.0024999"
- rpy="0 0 0" />
- <mass
- value="1.2351" />
- <inertia
- ixx="0.0041541"
- ixy="-7.1529E-06"
- ixz="-1.1135E-05"
- iyy="0.0031617"
- iyz="0.00015352"
- izz="0.0035434" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link5.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="0.79216 0.81961 0.93333 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link5.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint5"
- type="revolute">
- <origin
- xyz="0 0 0"
- rpy="1.5708 1.5708 0" />
- <parent
- link="Link4" />
- <child
- link="Link5" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-1.6"
- upper="0.75"
- effort="45.52"
- velocity="4.815" />
- </joint>
- <link
- name="Link6">
- <inertial>
- <origin
- xyz="0.048649 -0.00090428 0.27553"
- rpy="0 0 0" />
- <mass
- value="1.8877" />
- <inertia
- ixx="0.0086566"
- ixy="0.00012203"
- ixz="-0.00084157"
- iyy="0.0053122"
- iyz="0.00012437"
- izz="0.0064842" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://mr12urdf20240605/meshes/Link6.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://mr12urdf20240605/meshes/Link6.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint6"
- type="revolute">
- <origin
- xyz="0 0 0"
- rpy="1.5708 0 0" />
- <parent
- link="Link5" />
- <child
- link="Link6" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-2.1"
- upper="2.1"
- effort="32.64"
- velocity="23.655" />
- </joint>
- <joint
- name="joint_flp"
- type="fixed">
- <parent
- link="Link6"/>
- <child
- link="link_flp"/>
- <!-- 法兰盘 -->
- <origin rpy=" 0 0 3.1415926" xyz="0 0 0.100"/>
- </joint>
- <link name="link_flp">
- <collision>
- <geometry>
- <box size="0.0001 0.0001 0.0001"/>
- </geometry>
- <origin rpy="0 0 0" xyz="0 0 0"/>
- </collision>
- </link>
- <joint
- name="joint_end"
- type="fixed">
- <parent
- link="link_flp"/>
- <child
- link="link_end"/>
- <origin rpy="0.0 0.325888 3.1415926" xyz="-0.06371 0.004214 0.7387658"/>
- </joint>
- <link name="link_end">
- </link>
- <joint
- name="joint_end2"
- type="fixed">
- <parent
- link="link_end"/>
- <child
- link="link_end_now"/>
- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.01"/>
- </joint>
- <link name="link_end_now">
- </link>
- </robot>
|