batch 5: add arm_model newURDF

This commit is contained in:
xxxxm 2026-03-07 20:39:08 +08:00
parent 4aae0c5d68
commit 714c01b7d5
15 changed files with 829 additions and 0 deletions

View File

@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(newURDF)
find_package(catkin REQUIRED)
catkin_package()
find_package(roslaunch)
foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)

View File

@ -0,0 +1 @@
controller_joint_names: ['', 'j1', 'j2', 'j3', 'j4', 'j5', 'j6', ]

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,20 @@
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find newURDF)/urdf/newURDF.urdf" />
<node
name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find newURDF)/urdf.rviz" />
</launch>

View File

@ -0,0 +1,20 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find newURDF)/urdf/newURDF.urdf -urdf -model newURDF"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>

View File

@ -0,0 +1,21 @@
<package format="2">
<name>newURDF</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for newURDF</p>
<p>This package contains configuration data, 3D models and launch files
for newURDF robot</p>
</description>
<author>TODO</author>
<maintainer email="TODO@email.com" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>roslaunch</depend>
<depend>robot_state_publisher</depend>
<depend>rviz</depend>
<depend>joint_state_publisher_gui</depend>
<depend>gazebo</depend>
<export>
<architecture_independent />
</export>
</package>

View File

@ -0,0 +1,8 @@
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
base_link,0.097666,-1.0602,0.016983,0,0,0,1.0623,0.00202,7.846E-08,-1.6521E-08,0.0031488,-1.0021E-07,0.0051396,0,0,0,0,0,0,package://newURDF/meshes/base_link.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://newURDF/meshes/base_link.STL,,大Y模块-2,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
Link1,0.0070301,-0.00030378,0.044333,0,0,0,2.3117,0.0035548,1.4877E-06,3.269E-05,0.0024594,1.066E-06,0.0036305,0,0,0,0,0,0,package://newURDF/meshes/Link1.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://newURDF/meshes/Link1.STL,,一号臂驱动单元-1;3.1-二号臂驱动单元-1,坐标系base,基准轴base,j1,revolute,0.18701,-1.0602,0.042134,0,0,1.5708,base_link,0,0,1,60,3.14,-15.7,15.7,,,,,,,,
Link2,-9.2767E-06,-0.27664,0.019763,0,0,0,0.9007,0.0057226,-1.0789E-05,-6.9854E-13,0.00032946,-2.0483E-16,0.0060392,0,0,0,0,0,0,package://newURDF/meshes/Link2.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://newURDF/meshes/Link2.STL,,3.1-一号臂-1,坐标系2,基准轴URDF2,j2,revolute,-0.0208,0,0.085,-1.5708,0,-1.5708,Link1,0,0,1,60,3.14,-1.57,1.57,,,,,,,,
Link3,0.0016734,-0.086963,-0.059109,0,0,0,0.72964,0.00040609,-1.1866E-05,8.3967E-07,0.00028636,4.7151E-08,0.00030158,0,0,0,0,0,0,package://newURDF/meshes/Link3.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://newURDF/meshes/Link3.STL,,3.1-二号臂主臂-1,坐标系3,基准轴URDF3,j3,revolute,0,-0.404,0.0563,0,0,-1.5708,Link2,0,0,1,3,3.14,0,3,,,,,,,,
Link4,4.9724306803875E-05,-0.00207071321291896,0.143599808817138,0,0,0,0.60214796640085,0.000525809010016783,1.23868002227642E-08,-1.24134280805566E-08,0.000546950540891618,1.12515113310339E-06,0.000149799542930966,0,0,0,0,0,0,package://newURDF/meshes/Link4.STL,0.752941176470588,0.752941176470588,0.752941176470588,1,0,0,0,0,0,0,package://newURDF/meshes/Link4.STL,,3.1-二号臂回转臂-1,坐标系4,基准轴URDF4,j4,revolute,0.047775,-0.0905,-0.0355,-1.5708,0,-1.5708,Link3,0,0,1,3,3.14,-12.56,12.56,,,,,,,,
Link5,-1.00614222916379E-05,0.0581666861440572,-0.0240267717595721,0,0,0,0.218165546730634,8.12333089853061E-05,1.14300936029607E-08,-1.13719114058548E-08,8.12745528093048E-05,-5.01183167153332E-07,8.39758674297567E-05,0,0,0,0,0,0,package://newURDF/meshes/Link5.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://newURDF/meshes/Link5.STL,,三号臂-1/三号臂Y电机安装板-1;三号臂-1/三号臂Y电机固定板-1;三号臂-1/三号臂Y电机侧加固板-2;三号臂-1/三号臂P轴轴承内固定上板-1;三号臂-1/三号臂Y电机侧加固板-1;三号臂-1/4310 减速机-rau 3505 3d-20250718.stp-1/4310_-RAU_3505_3D_0001.stp-1/4310_-RAU_3505_3D0001.stp-1;三号臂-1/4310 减速机-rau 3505 3d-20250718.stp-1/4310_-RAU_3505_3D_0001.stp-1/4310__VER_B0001.stp-1;三号臂-1/4310 减速机-rau 3505 3d-20250718.stp-1/4310_-RAU_3505_3D_0001.stp-1/G43_V1_1_220606A.stp-1,坐标系5,基准轴URDF5,j5,revolute,0,0.023,0.241,1.5708,0,3.1416,Link4,0,0,1,3,3.14,-1.75,1.75,,,,,,,,
Link6,2.13317252848316E-05,0.000538972898537438,0.0999352955724812,0,0,0,0.575128999928036,0.00025728868876434,-1.85839768859793E-06,1.14575058864561E-07,0.000169254451988166,5.60715028730914E-08,0.000243919065707014,0,0,0,0,0,0,package://newURDF/meshes/Link6.STL,0.749019607843137,0.749019607843137,0.749019607843137,1,0,0,0,0,0,0,package://newURDF/meshes/Link6.STL,,机械爪3.1-2/C620电调_标件_01-1;机械爪3.1-2/夹爪固定板-1;机械爪3.1-2/滑轨外限位-2;机械爪3.1-2/夹爪固定板-2;机械爪3.1-2/6-6-40M3-6;机械爪3.1-2/滑轨外限位-1;机械爪3.1-2/爪侧盖板-2;机械爪3.1-2/爪侧盖板-1;机械爪3.1-2/6-6-40M3-5;机械爪3.1-2/6-6-21M3-11;机械爪3.1-2/6-6-21M3-10;机械爪3.1-2/承载翼板-4;机械爪3.1-2/6-6-40M3-4;机械爪3.1-2/6-6-21M3-9;机械爪3.1-2/6-6-40M3-3;机械爪3.1-2/6-6-40M3-2;机械爪3.1-2/6-6-40M3-1;机械爪3.1-2/承载翼板-3;机械爪3.1-2/承载翼板-2;机械爪3.1-2/6-6-21M3-12;机械爪3.1-2/6-6-21M3-8;机械爪3.1-2/6-6-21M3-6;机械爪3.1-2/6-6-21M3-5;机械爪3.1-2/6-6-21M3-4;机械爪3.1-2/6-6-21M3-3;机械爪3.1-2/从动杆-3;机械爪3.1-2/滑轨内限位-1;机械爪3.1-2/驱动杆盖板-1;机械爪3.1-2/爪盖板-4;机械爪3.1-2/6-6-21M3-2;机械爪3.1-2/承载翼板-1;机械爪3.1-2/6-6-21M3-7;机械爪3.1-2/6-6-21M3-1;机械爪3.1-2/爪盖板-3;机械爪3.1-2/驱动杆下-1;机械爪3.1-2/爪固定块上-2;机械爪3.1-2/爪固定块下-2;机械爪3.1-2/滑块MGN9C-3;机械爪3.1-2/爪固定块上-1;机械爪3.1-2/柔性爪-1;机械爪3.1-2/滑块MGN9C-2;机械爪3.1-2/爪连接块-1;机械爪3.1-2/柔性爪-2;机械爪3.1-2/爪固定块下-1;机械爪3.1-2/从动杆-2;机械爪3.1-2/驱动杆上-1;机械爪3.1-2/爪连接块-2;机械爪3.1-2/线轨MGN9-1;机械爪3.1-2/3508电机-1;机械爪3.1-2/承载板-1;机械爪3.1-2/线轨MGN9-2;机械爪3.1-2/电机转接板-1,坐标系6,基准轴URDF6,j6,revolute,1.4024E-05,0.1065,-0.022997,1.5708,0,3.1416,Link5,0,0,1,3,3.14,-12.56,12.56,,,,,,,,
1 Link Name Center of Mass X Center of Mass Y Center of Mass Z Center of Mass Roll Center of Mass Pitch Center of Mass Yaw Mass Moment Ixx Moment Ixy Moment Ixz Moment Iyy Moment Iyz Moment Izz Visual X Visual Y Visual Z Visual Roll Visual Pitch Visual Yaw Mesh Filename Color Red Color Green Color Blue Color Alpha Collision X Collision Y Collision Z Collision Roll Collision Pitch Collision Yaw Collision Mesh Filename Material Name SW Components Coordinate System Axis Name Joint Name Joint Type Joint Origin X Joint Origin Y Joint Origin Z Joint Origin Roll Joint Origin Pitch Joint Origin Yaw Parent Joint Axis X Joint Axis Y Joint Axis Z Limit Effort Limit Velocity Limit Lower Limit Upper Calibration rising Calibration falling Dynamics Damping Dynamics Friction Safety Soft Upper Safety Soft Lower Safety K Position Safety K Velocity
2 base_link 0.097666 -1.0602 0.016983 0 0 0 1.0623 0.00202 7.846E-08 -1.6521E-08 0.0031488 -1.0021E-07 0.0051396 0 0 0 0 0 0 package://newURDF/meshes/base_link.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://newURDF/meshes/base_link.STL 大Y模块-2 Origin_global 0 0 0 0 0 0 0 0 0
3 Link1 0.0070301 -0.00030378 0.044333 0 0 0 2.3117 0.0035548 1.4877E-06 3.269E-05 0.0024594 1.066E-06 0.0036305 0 0 0 0 0 0 package://newURDF/meshes/Link1.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://newURDF/meshes/Link1.STL 一号臂驱动单元-1;3.1-二号臂驱动单元-1 坐标系base 基准轴base j1 revolute 0.18701 -1.0602 0.042134 0 0 1.5708 base_link 0 0 1 60 3.14 -15.7 15.7
4 Link2 -9.2767E-06 -0.27664 0.019763 0 0 0 0.9007 0.0057226 -1.0789E-05 -6.9854E-13 0.00032946 -2.0483E-16 0.0060392 0 0 0 0 0 0 package://newURDF/meshes/Link2.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://newURDF/meshes/Link2.STL 3.1-一号臂-1 坐标系2 基准轴URDF2 j2 revolute -0.0208 0 0.085 -1.5708 0 -1.5708 Link1 0 0 1 60 3.14 -1.57 1.57
5 Link3 0.0016734 -0.086963 -0.059109 0 0 0 0.72964 0.00040609 -1.1866E-05 8.3967E-07 0.00028636 4.7151E-08 0.00030158 0 0 0 0 0 0 package://newURDF/meshes/Link3.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://newURDF/meshes/Link3.STL 3.1-二号臂主臂-1 坐标系3 基准轴URDF3 j3 revolute 0 -0.404 0.0563 0 0 -1.5708 Link2 0 0 1 3 3.14 0 3
6 Link4 4.9724306803875E-05 -0.00207071321291896 0.143599808817138 0 0 0 0.60214796640085 0.000525809010016783 1.23868002227642E-08 -1.24134280805566E-08 0.000546950540891618 1.12515113310339E-06 0.000149799542930966 0 0 0 0 0 0 package://newURDF/meshes/Link4.STL 0.752941176470588 0.752941176470588 0.752941176470588 1 0 0 0 0 0 0 package://newURDF/meshes/Link4.STL 3.1-二号臂回转臂-1 坐标系4 基准轴URDF4 j4 revolute 0.047775 -0.0905 -0.0355 -1.5708 0 -1.5708 Link3 0 0 1 3 3.14 -12.56 12.56
7 Link5 -1.00614222916379E-05 0.0581666861440572 -0.0240267717595721 0 0 0 0.218165546730634 8.12333089853061E-05 1.14300936029607E-08 -1.13719114058548E-08 8.12745528093048E-05 -5.01183167153332E-07 8.39758674297567E-05 0 0 0 0 0 0 package://newURDF/meshes/Link5.STL 0.898039215686275 0.917647058823529 0.929411764705882 1 0 0 0 0 0 0 package://newURDF/meshes/Link5.STL 三号臂-1/三号臂Y电机安装板-1;三号臂-1/三号臂Y电机固定板-1;三号臂-1/三号臂Y电机侧加固板-2;三号臂-1/三号臂P轴轴承内固定上板-1;三号臂-1/三号臂Y电机侧加固板-1;三号臂-1/4310 减速机-rau 3505 3d-20250718.stp-1/4310_-RAU_3505_3D_0001.stp-1/4310_-RAU_3505_3D0001.stp-1;三号臂-1/4310 减速机-rau 3505 3d-20250718.stp-1/4310_-RAU_3505_3D_0001.stp-1/4310__VER_B0001.stp-1;三号臂-1/4310 减速机-rau 3505 3d-20250718.stp-1/4310_-RAU_3505_3D_0001.stp-1/G43_V1_1_220606A.stp-1 坐标系5 基准轴URDF5 j5 revolute 0 0.023 0.241 1.5708 0 3.1416 Link4 0 0 1 3 3.14 -1.75 1.75
8 Link6 2.13317252848316E-05 0.000538972898537438 0.0999352955724812 0 0 0 0.575128999928036 0.00025728868876434 -1.85839768859793E-06 1.14575058864561E-07 0.000169254451988166 5.60715028730914E-08 0.000243919065707014 0 0 0 0 0 0 package://newURDF/meshes/Link6.STL 0.749019607843137 0.749019607843137 0.749019607843137 1 0 0 0 0 0 0 package://newURDF/meshes/Link6.STL 机械爪3.1-2/C620电调_标件_01-1;机械爪3.1-2/夹爪固定板-1;机械爪3.1-2/滑轨外限位-2;机械爪3.1-2/夹爪固定板-2;机械爪3.1-2/6-6-40M3-6;机械爪3.1-2/滑轨外限位-1;机械爪3.1-2/爪侧盖板-2;机械爪3.1-2/爪侧盖板-1;机械爪3.1-2/6-6-40M3-5;机械爪3.1-2/6-6-21M3-11;机械爪3.1-2/6-6-21M3-10;机械爪3.1-2/承载翼板-4;机械爪3.1-2/6-6-40M3-4;机械爪3.1-2/6-6-21M3-9;机械爪3.1-2/6-6-40M3-3;机械爪3.1-2/6-6-40M3-2;机械爪3.1-2/6-6-40M3-1;机械爪3.1-2/承载翼板-3;机械爪3.1-2/承载翼板-2;机械爪3.1-2/6-6-21M3-12;机械爪3.1-2/6-6-21M3-8;机械爪3.1-2/6-6-21M3-6;机械爪3.1-2/6-6-21M3-5;机械爪3.1-2/6-6-21M3-4;机械爪3.1-2/6-6-21M3-3;机械爪3.1-2/从动杆-3;机械爪3.1-2/滑轨内限位-1;机械爪3.1-2/驱动杆盖板-1;机械爪3.1-2/爪盖板-4;机械爪3.1-2/6-6-21M3-2;机械爪3.1-2/承载翼板-1;机械爪3.1-2/6-6-21M3-7;机械爪3.1-2/6-6-21M3-1;机械爪3.1-2/爪盖板-3;机械爪3.1-2/驱动杆下-1;机械爪3.1-2/爪固定块上-2;机械爪3.1-2/爪固定块下-2;机械爪3.1-2/滑块MGN9C-3;机械爪3.1-2/爪固定块上-1;机械爪3.1-2/柔性爪-1;机械爪3.1-2/滑块MGN9C-2;机械爪3.1-2/爪连接块-1;机械爪3.1-2/柔性爪-2;机械爪3.1-2/爪固定块下-1;机械爪3.1-2/从动杆-2;机械爪3.1-2/驱动杆上-1;机械爪3.1-2/爪连接块-2;机械爪3.1-2/线轨MGN9-1;机械爪3.1-2/3508电机-1;机械爪3.1-2/承载板-1;机械爪3.1-2/线轨MGN9-2;机械爪3.1-2/电机转接板-1 坐标系6 基准轴URDF6 j6 revolute 1.4024E-05 0.1065 -0.022997 1.5708 0 3.1416 Link5 0 0 1 3 3.14 -12.56 12.56

View File

@ -0,0 +1,395 @@
<?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>