batch 4: add arm_model fix2026224

This commit is contained in:
xxxxm 2026-03-07 20:37:20 +08:00
parent bd18d63a6d
commit 4aae0c5d68
19 changed files with 734 additions and 0 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 427 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 48 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 39 KiB

View File

@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(arm)
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 arm)/urdf/arm.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 arm)/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 arm)/urdf/arm.urdf -urdf -model arm"
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>arm</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for arm</p>
<p>This package contains configuration data, 3D models and launch files
for arm 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,-2.2084E-06,0.089343,0.015349,0,0,0,1.0623,0.0031488,-7.846E-08,-1.0021E-07,0.00202,1.6521E-08,0.0051396,0,0,0,0,0,0,package://arm/meshes/base_link.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://arm/meshes/base_link.STL,,大Y模块-2,坐标系base,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
Link1,0.0066971,-0.00030098,0.044241,0,0,0,2.3045,0.0035406,1.4877E-06,1.0878E-05,0.002472,1.066E-06,0.0036573,0,0,0,0,0,0,package://arm/meshes/Link1.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://arm/meshes/Link1.STL,,一号臂驱动单元-1;3.1-二号臂驱动单元-1,坐标系1,基准轴1,j1,revolute,0,0,0.0405,0,0,0,base_link,0,0,1,60,3.14,-15.7,15.7,,,,,,,,
Link2,-3.7501E-08,-0.26586,0.00044116,0,0,0,0.8903,0.0051781,-7.1373E-06,-6.9776E-13,0.00032382,-2.0393E-15,0.0054891,0,0,0,0,0,0,package://arm/meshes/Link2.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://arm/meshes/Link2.STL,,3.1-一号臂-1,坐标系2,基准轴2,j2,revolute,-0.0014,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.025004,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://arm/meshes/Link3.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://arm/meshes/Link3.STL,,3.1-二号臂主臂-1,坐标系3,基准轴3,j3,revolute,0,-0.388,0.002795,0,0,-1.5708,Link2,0,0,-1,60,3.14,0,3.14,,,,,,,,
Link4,4.9724E-05,-0.0020707,0.1436,0,0,0,0.60215,0.00052581,1.2387E-08,-1.2413E-08,0.00054695,1.1252E-06,0.0001498,0,0,0,0,0,0,package://arm/meshes/Link4.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://arm/meshes/Link4.STL,,3.1-二号臂回转臂-1,坐标系4,基准轴4,j4,revolute,0.047775,-0.0905,-0.001395,-1.5708,0,-1.5708,Link3,0,0,1,20,3.14,0,6.28,,,,,,,,
Link5,-1.7073E-05,0.058169,0.0029732,0,0,0,0.21817,8.1233E-05,1.143E-08,-1.1372E-08,8.1275E-05,-5.0118E-07,8.3976E-05,0,0,0,0,0,0,package://arm/meshes/Link5.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://arm/meshes/Link5.STL,,三号臂-1,坐标系5,基准轴5,j5,revolute,0,-0.004,0.241,1.5708,0,-3.1416,Link4,0,0,-1,20,3.14,-1.75,1.75,,,,,,,,
Link6,2.1332E-05,0.00053897,0.099935,0,0,0,0.57513,0.00025729,-1.8584E-06,1.1458E-07,0.00016925,5.6071E-08,0.00024392,0,0,0,0,0,0,package://arm/meshes/Link6.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://arm/meshes/Link6.STL,,机械爪3.1-2,坐标系6,基准轴6,j6,revolute,0,0.1065,0.0040025,1.5708,0,3.1416,Link5,0,0,-1,20,3.14,0,6.3,,,,,,,,
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 -2.2084E-06 0.089343 0.015349 0 0 0 1.0623 0.0031488 -7.846E-08 -1.0021E-07 0.00202 1.6521E-08 0.0051396 0 0 0 0 0 0 package://arm/meshes/base_link.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://arm/meshes/base_link.STL 大Y模块-2 坐标系base 0 0 0 0 0 0 0 0 0
3 Link1 0.0066971 -0.00030098 0.044241 0 0 0 2.3045 0.0035406 1.4877E-06 1.0878E-05 0.002472 1.066E-06 0.0036573 0 0 0 0 0 0 package://arm/meshes/Link1.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://arm/meshes/Link1.STL 一号臂驱动单元-1;3.1-二号臂驱动单元-1 坐标系1 基准轴1 j1 revolute 0 0 0.0405 0 0 0 base_link 0 0 1 60 3.14 -15.7 15.7
4 Link2 -3.7501E-08 -0.26586 0.00044116 0 0 0 0.8903 0.0051781 -7.1373E-06 -6.9776E-13 0.00032382 -2.0393E-15 0.0054891 0 0 0 0 0 0 package://arm/meshes/Link2.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://arm/meshes/Link2.STL 3.1-一号臂-1 坐标系2 基准轴2 j2 revolute -0.0014 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.025004 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://arm/meshes/Link3.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://arm/meshes/Link3.STL 3.1-二号臂主臂-1 坐标系3 基准轴3 j3 revolute 0 -0.388 0.002795 0 0 -1.5708 Link2 0 0 -1 60 3.14 0 3.14
6 Link4 4.9724E-05 -0.0020707 0.1436 0 0 0 0.60215 0.00052581 1.2387E-08 -1.2413E-08 0.00054695 1.1252E-06 0.0001498 0 0 0 0 0 0 package://arm/meshes/Link4.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://arm/meshes/Link4.STL 3.1-二号臂回转臂-1 坐标系4 基准轴4 j4 revolute 0.047775 -0.0905 -0.001395 -1.5708 0 -1.5708 Link3 0 0 1 20 3.14 0 6.28
7 Link5 -1.7073E-05 0.058169 0.0029732 0 0 0 0.21817 8.1233E-05 1.143E-08 -1.1372E-08 8.1275E-05 -5.0118E-07 8.3976E-05 0 0 0 0 0 0 package://arm/meshes/Link5.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://arm/meshes/Link5.STL 三号臂-1 坐标系5 基准轴5 j5 revolute 0 -0.004 0.241 1.5708 0 -3.1416 Link4 0 0 -1 20 3.14 -1.75 1.75
8 Link6 2.1332E-05 0.00053897 0.099935 0 0 0 0.57513 0.00025729 -1.8584E-06 1.1458E-07 0.00016925 5.6071E-08 0.00024392 0 0 0 0 0 0 package://arm/meshes/Link6.STL 0.75294 0.75294 0.75294 1 0 0 0 0 0 0 package://arm/meshes/Link6.STL 机械爪3.1-2 坐标系6 基准轴6 j6 revolute 0 0.1065 0.0040025 1.5708 0 3.1416 Link5 0 0 -1 20 3.14 0 6.3

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="arm">
<link
name="base_link">
<inertial>
<origin
xyz="-2.2084E-06 0.089343 0.015349"
rpy="0 0 0" />
<mass
value="1.0623" />
<inertia
ixx="0.0031488"
ixy="-7.846E-08"
ixz="-1.0021E-07"
iyy="0.00202"
iyz="1.6521E-08"
izz="0.0051396" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm/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://arm/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="Link1">
<inertial>
<origin
xyz="0.0066971 -0.00030098 0.044241"
rpy="0 0 0" />
<mass
value="2.3045" />
<inertia
ixx="0.0035406"
ixy="1.4877E-06"
ixz="1.0878E-05"
iyy="0.002472"
iyz="1.066E-06"
izz="0.0036573" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm/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://arm/meshes/Link1.STL" />
</geometry>
</collision>
</link>
<joint
name="j1"
type="revolute">
<origin
xyz="0 0 0.0405"
rpy="0 0 0" />
<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="-3.7501E-08 -0.26586 0.00044116"
rpy="0 0 0" />
<mass
value="0.8903" />
<inertia
ixx="0.0051781"
ixy="-7.1373E-06"
ixz="-6.9776E-13"
iyy="0.00032382"
iyz="-2.0393E-15"
izz="0.0054891" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm/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://arm/meshes/Link2.STL" />
</geometry>
</collision>
</link>
<joint
name="j2"
type="revolute">
<origin
xyz="-0.0014 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.025004"
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://arm/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://arm/meshes/Link3.STL" />
</geometry>
</collision>
</link>
<joint
name="j3"
type="revolute">
<origin
xyz="0 -0.388 0.002795"
rpy="0 0 -1.5708" />
<parent
link="Link2" />
<child
link="Link3" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="3.00"
effort="60"
velocity="3.14" />
</joint>
<link
name="Link4">
<inertial>
<origin
xyz="4.9724E-05 -0.0020707 0.1436"
rpy="0 0 0" />
<mass
value="0.60215" />
<inertia
ixx="0.00052581"
ixy="1.2387E-08"
ixz="-1.2413E-08"
iyy="0.00054695"
iyz="1.1252E-06"
izz="0.0001498" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm/meshes/Link4.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://arm/meshes/Link4.STL" />
</geometry>
</collision>
</link>
<joint
name="j4"
type="revolute">
<origin
xyz="0.047775 -0.0905 -0.001395"
rpy="-1.5708 0 -1.5708" />
<parent
link="Link3" />
<child
link="Link4" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="6.28"
effort="20"
velocity="3.14" />
</joint>
<link
name="Link5">
<inertial>
<origin
xyz="-1.7073E-05 0.058169 0.0029732"
rpy="0 0 0" />
<mass
value="0.21817" />
<inertia
ixx="8.1233E-05"
ixy="1.143E-08"
ixz="-1.1372E-08"
iyy="8.1275E-05"
iyz="-5.0118E-07"
izz="8.3976E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm/meshes/Link5.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://arm/meshes/Link5.STL" />
</geometry>
</collision>
</link>
<joint
name="j5"
type="revolute">
<origin
xyz="0 -0.004 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="20"
velocity="3.14" />
</joint>
<link
name="Link6">
<inertial>
<origin
xyz="2.1332E-05 0.00053897 0.099935"
rpy="0 0 0" />
<mass
value="0.57513" />
<inertia
ixx="0.00025729"
ixy="-1.8584E-06"
ixz="1.1458E-07"
iyy="0.00016925"
iyz="5.6071E-08"
izz="0.00024392" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm/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://arm/meshes/Link6.STL" />
</geometry>
</collision>
</link>
<joint
name="j6"
type="revolute">
<origin
xyz="0 0.1065 0.0040025"
rpy="1.5708 0 3.1416" />
<parent
link="Link5" />
<child
link="Link6" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="6.3"
effort="20"
velocity="3.14" />
</joint>
</robot>