IsaacSim support (#13)
Fix enactic/openarm_isaac_lab#2 * Change dae file * Change physical parameter Reported by @Bakel-Bakel. Thanks!!!
This commit is contained in:
parent
af6f035806
commit
c8bc82defa
@ -53,7 +53,7 @@ link3:
|
|||||||
origin:
|
origin:
|
||||||
x: -0.002104752099628911
|
x: -0.002104752099628911
|
||||||
y: 0.0005549085042607548
|
y: 0.0005549085042607548
|
||||||
z: 0.08847470545721961
|
z: 0.09047470545721961
|
||||||
roll: 0.0
|
roll: 0.0
|
||||||
pitch: 0.0
|
pitch: 0.0
|
||||||
yaw: 0.0
|
yaw: 0.0
|
||||||
@ -74,7 +74,7 @@ link4:
|
|||||||
roll: 0.0
|
roll: 0.0
|
||||||
pitch: 0.0
|
pitch: 0.0
|
||||||
yaw: 0.0
|
yaw: 0.0
|
||||||
mass: 0.5598534566833373
|
mass: 0.6348534566833373
|
||||||
inertia:
|
inertia:
|
||||||
xx: 0.000623
|
xx: 0.000623
|
||||||
xy: -1.0e-06
|
xy: -1.0e-06
|
||||||
@ -91,7 +91,7 @@ link5:
|
|||||||
roll: 0.0
|
roll: 0.0
|
||||||
pitch: 0.0
|
pitch: 0.0
|
||||||
yaw: 0.0
|
yaw: 0.0
|
||||||
mass: 0.5506588026168502
|
mass: 0.6156588026168502
|
||||||
inertia:
|
inertia:
|
||||||
xx: 0.000423
|
xx: 0.000423
|
||||||
xy: -8.0e-06
|
xy: -8.0e-06
|
||||||
@ -108,7 +108,7 @@ link6:
|
|||||||
roll: 0.0
|
roll: 0.0
|
||||||
pitch: 0.0
|
pitch: 0.0
|
||||||
yaw: 0.0
|
yaw: 0.0
|
||||||
mass: 0.385202773187987
|
mass: 0.475202773187987
|
||||||
inertia:
|
inertia:
|
||||||
xx: 0.000143
|
xx: 0.000143
|
||||||
xy: 1e-06
|
xy: 1e-06
|
||||||
@ -125,7 +125,7 @@ link7:
|
|||||||
roll: 0.0
|
roll: 0.0
|
||||||
pitch: 0.0
|
pitch: 0.0
|
||||||
yaw: 0.0
|
yaw: 0.0
|
||||||
mass: 0.3859771327380578
|
mass: 0.4659771327380578
|
||||||
inertia:
|
inertia:
|
||||||
xx: 0.000639
|
xx: 0.000639
|
||||||
xy: 1e-06
|
xy: 1e-06
|
||||||
|
|||||||
@ -2,15 +2,15 @@ hand:
|
|||||||
origin:
|
origin:
|
||||||
x: 0.0
|
x: 0.0
|
||||||
y: 0.002
|
y: 0.002
|
||||||
z: 0.019
|
z: 0.03
|
||||||
roll: 0
|
roll: 0
|
||||||
pitch: 0
|
pitch: 0
|
||||||
yaw: 0
|
yaw: 0
|
||||||
mass: 0.3
|
mass: 0.35
|
||||||
inertia:
|
inertia:
|
||||||
xx: 0.0001
|
xx: 0.0002473
|
||||||
yy: 0.00025
|
yy: 1.763e-05
|
||||||
zz: 0.00017
|
zz: 0.0002521
|
||||||
xy: 1e-06
|
xy: 1e-06
|
||||||
xz: 1e-06
|
xz: 1e-06
|
||||||
yz: 1e-06
|
yz: 1e-06
|
||||||
|
|||||||
@ -10,7 +10,7 @@
|
|||||||
hand:
|
hand:
|
||||||
kinematic:
|
kinematic:
|
||||||
x: 0.0
|
x: 0.0
|
||||||
y: 0.005
|
y: 0.00
|
||||||
z: -0.6585
|
z: -0.6585
|
||||||
roll: 0.0
|
roll: 0.0
|
||||||
pitch: 0.0
|
pitch: 0.0
|
||||||
|
|||||||
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
@ -106,13 +106,13 @@
|
|||||||
<xacro:openarm-limits name="joint7" config="${joint_limits}" />
|
<xacro:openarm-limits name="joint7" config="${joint_limits}" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="${prefix}link8"/>
|
<!-- <link name="${prefix}link8"/>
|
||||||
|
|
||||||
<joint name="${prefix}joint8" type="fixed">
|
<joint name="${prefix}joint8" type="fixed">
|
||||||
<xacro:openarm-kinematics name="joint8" config="${kinematics}" />
|
<xacro:openarm-kinematics name="joint8" config="${kinematics}" />
|
||||||
<parent link="${prefix}link7" />
|
<parent link="${prefix}link7" />
|
||||||
<child link="${prefix}link8" />
|
<child link="${prefix}link8" />
|
||||||
</joint>
|
</joint> -->
|
||||||
|
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@ -67,7 +67,7 @@
|
|||||||
<joint name="${ee_prefix}finger_joint1" type="prismatic">
|
<joint name="${ee_prefix}finger_joint1" type="prismatic">
|
||||||
<parent link="${ee_prefix}hand" />
|
<parent link="${ee_prefix}hand" />
|
||||||
<child link="${ee_prefix}right_finger" />
|
<child link="${ee_prefix}right_finger" />
|
||||||
<origin xyz="0 0.00 0.015" rpy="0 0 0" />
|
<origin xyz="0 -0.006 0.015" rpy="0 0 0" />
|
||||||
<axis xyz="0 -1 0" />
|
<axis xyz="0 -1 0" />
|
||||||
<limit effort="333" lower="0.0" upper="0.044" velocity="10.0" />
|
<limit effort="333" lower="0.0" upper="0.044" velocity="10.0" />
|
||||||
</joint>
|
</joint>
|
||||||
@ -75,7 +75,7 @@
|
|||||||
<joint name="${ee_prefix}finger_joint2" type="prismatic">
|
<joint name="${ee_prefix}finger_joint2" type="prismatic">
|
||||||
<parent link="${ee_prefix}hand" />
|
<parent link="${ee_prefix}hand" />
|
||||||
<child link="${ee_prefix}left_finger" />
|
<child link="${ee_prefix}left_finger" />
|
||||||
<origin xyz="0 0.012 0.015" rpy="0 0 0" />
|
<origin xyz="0 0.006 0.015" rpy="0 0 0" />
|
||||||
<axis xyz="0 1 0" />
|
<axis xyz="0 1 0" />
|
||||||
<limit effort="333" lower="0.0" upper="0.044" velocity="10.0" />
|
<limit effort="333" lower="0.0" upper="0.044" velocity="10.0" />
|
||||||
<mimic joint="${ee_prefix}finger_joint1" />
|
<mimic joint="${ee_prefix}finger_joint1" />
|
||||||
|
|||||||
@ -5,7 +5,7 @@
|
|||||||
<xacro:arg name="special_connection" default="" />
|
<xacro:arg name="special_connection" default="" />
|
||||||
|
|
||||||
<!-- Position offset between ee and parent frame -->
|
<!-- Position offset between ee and parent frame -->
|
||||||
<xacro:arg name="xyz_ee" default="0 -0.025 0.1001" />
|
<xacro:arg name="xyz_ee" default="0 -0.0 0.1001" />
|
||||||
|
|
||||||
<!-- Rotation offset between ee and parent frame -->
|
<!-- Rotation offset between ee and parent frame -->
|
||||||
<xacro:arg name="rpy_ee" default= "0 0 0" />
|
<xacro:arg name="rpy_ee" default= "0 0 0" />
|
||||||
|
|||||||
@ -112,7 +112,7 @@
|
|||||||
|
|
||||||
<xacro:if value="$(eval hand and ee_type == 'openarm_hand')">
|
<xacro:if value="$(eval hand and ee_type == 'openarm_hand')">
|
||||||
<xacro:openarm_hand
|
<xacro:openarm_hand
|
||||||
connected_to="openarm_left_link8"
|
connected_to="openarm_left_link7"
|
||||||
arm_type="${arm_type}"
|
arm_type="${arm_type}"
|
||||||
arm_prefix="left_"
|
arm_prefix="left_"
|
||||||
ee_type="${ee_type}"
|
ee_type="${ee_type}"
|
||||||
@ -125,7 +125,7 @@
|
|||||||
description_pkg="$(arg description_pkg)"
|
description_pkg="$(arg description_pkg)"
|
||||||
/>
|
/>
|
||||||
<xacro:openarm_hand
|
<xacro:openarm_hand
|
||||||
connected_to="openarm_right_link8"
|
connected_to="openarm_right_link7"
|
||||||
arm_type="${arm_type}"
|
arm_type="${arm_type}"
|
||||||
arm_prefix="right_"
|
arm_prefix="right_"
|
||||||
ee_type="${ee_type}"
|
ee_type="${ee_type}"
|
||||||
@ -170,8 +170,8 @@
|
|||||||
<xacro:if value="${hand and ee_type == 'openarm_hand'}">
|
<xacro:if value="${hand and ee_type == 'openarm_hand'}">
|
||||||
|
|
||||||
<xacro:property name="special_connection" value="$(arg special_connection)" />
|
<xacro:property name="special_connection" value="$(arg special_connection)" />
|
||||||
<!-- <xacro:property name="connection" value="${special_connection if special_connection != '' else arm_type + '_link8'}" /> -->
|
<!-- <xacro:property name="connection" value="${special_connection if special_connection != '' else arm_type + '_link7'}" /> -->
|
||||||
<xacro:property name="connection" value="${special_connection if special_connection != '' else 'openarm' + '_link8'}" />
|
<xacro:property name="connection" value="${special_connection if special_connection != '' else 'openarm' + '_link7'}" />
|
||||||
|
|
||||||
<xacro:if value="$(eval hand and ee_type == 'openarm_hand')">
|
<xacro:if value="$(eval hand and ee_type == 'openarm_hand')">
|
||||||
<xacro:openarm_hand
|
<xacro:openarm_hand
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user