mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2026-02-12 10:45:10 +00:00
添加机械臂和移液站
This commit is contained in:
@@ -0,0 +1,43 @@
|
||||
kinematics:
|
||||
shoulder:
|
||||
x: 0
|
||||
y: 0
|
||||
z: 0.1530
|
||||
roll: 0
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
upperarm:
|
||||
x: 0
|
||||
y: 0
|
||||
z: 0
|
||||
roll: 1.570796326589793
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
forearm:
|
||||
x: -0.2700
|
||||
y: 0
|
||||
z: 0
|
||||
roll: 0
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
wrist_1:
|
||||
x: -0.2575
|
||||
y: 0
|
||||
z: 0.1445
|
||||
roll: 0
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
wrist_2:
|
||||
x: 0
|
||||
y: -0.0965
|
||||
z: 0
|
||||
roll: 1.570796326589793
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
wrist_3:
|
||||
x: 0
|
||||
y: 0.0920
|
||||
z: 0
|
||||
roll: -1.570796326589793
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
@@ -0,0 +1,61 @@
|
||||
joint_limits:
|
||||
shoulder_pan_joint:
|
||||
# acceleration limits are not publicly available
|
||||
has_acceleration_limits: false
|
||||
has_effort_limits: true
|
||||
has_position_limits: true
|
||||
has_velocity_limits: true
|
||||
max_effort: 56.0
|
||||
max_position: !degrees 360.0
|
||||
max_velocity: !degrees 180.0
|
||||
min_position: !degrees -360.0
|
||||
shoulder_lift_joint:
|
||||
# acceleration limits are not publicly available
|
||||
has_acceleration_limits: false
|
||||
has_effort_limits: true
|
||||
has_position_limits: true
|
||||
has_velocity_limits: true
|
||||
max_effort: 56.0
|
||||
max_position: !degrees 360.0
|
||||
max_velocity: !degrees 180.0
|
||||
min_position: !degrees -360.0
|
||||
elbow_joint:
|
||||
# acceleration limits are not publicly available
|
||||
has_acceleration_limits: false
|
||||
has_effort_limits: true
|
||||
has_position_limits: true
|
||||
has_velocity_limits: true
|
||||
max_effort: 28.0
|
||||
max_position: !degrees 180.0
|
||||
max_velocity: !degrees 180.0
|
||||
min_position: !degrees -180.0
|
||||
wrist_1_joint:
|
||||
# acceleration limits are not publicly available
|
||||
has_acceleration_limits: false
|
||||
has_effort_limits: true
|
||||
has_position_limits: true
|
||||
has_velocity_limits: true
|
||||
max_effort: 12.0
|
||||
max_position: !degrees 360.0
|
||||
max_velocity: !degrees 360.0
|
||||
min_position: !degrees -360.0
|
||||
wrist_2_joint:
|
||||
# acceleration limits are not publicly available
|
||||
has_acceleration_limits: false
|
||||
has_effort_limits: true
|
||||
has_position_limits: true
|
||||
has_velocity_limits: true
|
||||
max_effort: 12.0
|
||||
max_position: !degrees 360.0
|
||||
max_velocity: !degrees 360.0
|
||||
min_position: !degrees -360.0
|
||||
wrist_3_joint:
|
||||
# acceleration limits are not publicly available
|
||||
has_acceleration_limits: false
|
||||
has_effort_limits: true
|
||||
has_position_limits: true
|
||||
has_velocity_limits: true
|
||||
max_effort: 12.0
|
||||
max_position: !degrees 360.0
|
||||
max_velocity: !degrees 360.0
|
||||
min_position: !degrees -360.0
|
||||
@@ -0,0 +1,99 @@
|
||||
# Physical parameters
|
||||
|
||||
dh_parameters:
|
||||
d1: 0.1530
|
||||
a2: -0.2700
|
||||
a3: -0.2575
|
||||
d4: 0.1445
|
||||
d5: 0.0965
|
||||
d6: 0.0920
|
||||
|
||||
inertia_parameters:
|
||||
base_mass: 0.358193760044688 # base mass, base inertia, base cog might be incorrect
|
||||
shoulder_mass: 3.095
|
||||
upperarm_mass: 5.073
|
||||
forearm_mass: 2.425
|
||||
wrist_1_mass: 1.559
|
||||
wrist_2_mass: 1.447
|
||||
wrist_3_mass: 0.500
|
||||
|
||||
inertia:
|
||||
base:
|
||||
ixx: 0.000549739542527148
|
||||
ixy: 8.03741216179988E-08
|
||||
ixz: -9.14780809458034E-06
|
||||
iyy: 0.000533024165382036
|
||||
iyz: 3.46908903534662E-07
|
||||
izz: 0.000655188839052244
|
||||
shoulder:
|
||||
ixx: 0.007958
|
||||
ixy: 5.734E-06
|
||||
ixz: 3.024E-06
|
||||
iyy: 0.00484
|
||||
iyz: -1.77E-05
|
||||
izz: 0.006686
|
||||
upperarm:
|
||||
ixx: 0.074168
|
||||
ixy: -7.5E-06
|
||||
ixz: -0.065579
|
||||
iyy: 0.21937
|
||||
iyz: -2.19E-05
|
||||
izz: 0.15104
|
||||
forearm:
|
||||
ixx: 0.005082
|
||||
ixy: -2.7E-06
|
||||
ixz: -0.0056236
|
||||
iyy: 0.0924207
|
||||
iyz: -1.726E-06
|
||||
izz: 0.0897559
|
||||
wrist_1:
|
||||
ixx: 0.0045009
|
||||
ixy: 1.96E-06
|
||||
ixz: -2.646E-06
|
||||
iyy: 0.0042164
|
||||
iyz: -3.58E-07
|
||||
izz: 0.0014538
|
||||
wrist_2:
|
||||
ixx: 0.0023787
|
||||
ixy: 1.953E-06
|
||||
ixz: 2.643E-06
|
||||
iyy: 0.0020859
|
||||
iyz: 5.584E-06
|
||||
izz: 0.0013191
|
||||
wrist_3:
|
||||
ixx: 0.001431
|
||||
ixy: -2.32E-07
|
||||
ixz: 7.955E-06
|
||||
iyy: 0.0014299
|
||||
iyz: 1.266E-06
|
||||
izz: 0.0003265
|
||||
|
||||
center_of_mass:
|
||||
base_cog:
|
||||
x: -0.000721181367009438
|
||||
y: 1.78114684963572E-05
|
||||
z: 0.0546249293265112
|
||||
shoulder_cog:
|
||||
x: 3.7E-05
|
||||
y: -0.0149
|
||||
z: -0.0105
|
||||
upperarm_cog:
|
||||
x: -0.11596
|
||||
y: -2.6E-05
|
||||
z: 0.1148
|
||||
forearm_cog:
|
||||
x: -0.1542
|
||||
y: 1.4E-05
|
||||
z: 0.0238
|
||||
wrist_1_cog:
|
||||
x: 1.3E-05
|
||||
y: -0.00479
|
||||
z: -0.02274
|
||||
wrist_2_cog:
|
||||
x: -1.4E-05
|
||||
y: 0.0051
|
||||
z: -0.0127
|
||||
wrist_3_cog:
|
||||
x: -0.000684
|
||||
y: -0.000175
|
||||
z: -0.0423
|
||||
@@ -0,0 +1,92 @@
|
||||
mesh_files:
|
||||
base:
|
||||
visual:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/visual/base.dae
|
||||
material:
|
||||
name: "LightGrey"
|
||||
color: "0.7 0.7 0.7 1.0"
|
||||
collision:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/collision/base.stl
|
||||
|
||||
shoulder:
|
||||
visual:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/visual/shoulder.dae
|
||||
material:
|
||||
name: "LightGrey"
|
||||
color: "0.7 0.7 0.7 1.0"
|
||||
collision:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/collision/shoulder.stl
|
||||
|
||||
upperarm:
|
||||
visual:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/visual/upperarm.dae
|
||||
material:
|
||||
name: "LightGrey"
|
||||
color: "0.7 0.7 0.7 1.0"
|
||||
collision:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/collision/upperarm.stl
|
||||
mesh_files:
|
||||
|
||||
forearm:
|
||||
visual:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/visual/forearm.dae
|
||||
material:
|
||||
name: "LightGrey"
|
||||
color: "0.7 0.7 0.7 1.0"
|
||||
collision:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/collision/forearm.stl
|
||||
|
||||
wrist_1:
|
||||
visual:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/visual/wrist1.dae
|
||||
material:
|
||||
name: "LightGrey"
|
||||
color: "0.7 0.7 0.7 1.0"
|
||||
collision:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/collision/wrist1.stl
|
||||
|
||||
wrist_2:
|
||||
visual:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/visual/wrist2.dae
|
||||
material:
|
||||
name: "LightGrey"
|
||||
color: "0.7 0.7 0.7 1.0"
|
||||
collision:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/collision/wrist2.stl
|
||||
|
||||
wrist_3:
|
||||
visual:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/visual/wrist3.dae
|
||||
material:
|
||||
name: "LightGrey"
|
||||
color: "0.7 0.7 0.7 1.0"
|
||||
collision:
|
||||
mesh:
|
||||
package: eli_cs_robot_description
|
||||
path: meshes/cs63/collision/wrist3.stl
|
||||
Reference in New Issue
Block a user