Skip to content

Commit

Permalink
Remove comments to workaround ros2/launch_ros#214
Browse files Browse the repository at this point in the history
  • Loading branch information
jordan-palacios committed Feb 8, 2021
1 parent 7feaa14 commit 64777fc
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 13 deletions.
10 changes: 5 additions & 5 deletions urdf/actuators.urdf.xacro
Expand Up @@ -14,7 +14,7 @@
<xacro:macro name="thumb_actuator" params="name parent *origin">
<xacro:actuator_impl parent="${parent}" name="${name}">
<xacro:insert_block name="origin" />
<limit lower="${-150 * deg_to_rad}" upper="${360 * deg_to_rad}" effort="2.0" velocity="3.35" /> <!-- TODO: Tune effort -->
<limit lower="${-150 * deg_to_rad}" upper="${360 * deg_to_rad}" effort="2.0" velocity="3.35" />
<safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-150.0 * deg_to_rad}"
Expand All @@ -26,7 +26,7 @@
<xacro:macro name="index_actuator" params="name parent *origin">
<xacro:actuator_impl parent="${parent}" name="${name}">
<xacro:insert_block name="origin" />
<limit lower="${-175 * deg_to_rad}" upper="${390 * deg_to_rad}" effort="2.0" velocity="3.35" /> <!-- TODO: Tune effort -->
<limit lower="${-175 * deg_to_rad}" upper="${390 * deg_to_rad}" effort="2.0" velocity="3.35" />
<safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-175.0 * deg_to_rad}"
Expand All @@ -38,7 +38,7 @@
<xacro:macro name="mrl_actuator" params="name parent *origin">
<xacro:actuator_impl parent="${parent}" name="${name}">
<xacro:insert_block name="origin" />
<limit lower="${-145 * deg_to_rad}" upper="${530 * deg_to_rad}" effort="2.0" velocity="3.56" /> <!-- TODO: Tune effort -->
<limit lower="${-145 * deg_to_rad}" upper="${530 * deg_to_rad}" effort="2.0" velocity="3.56" />
<safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-145 * deg_to_rad}"
Expand All @@ -63,14 +63,14 @@
<xacro:insert_block name="origin" />
<axis xyz="0 0 1" />
<xacro:insert_block name="limit" />
<dynamics friction="0.0" damping="0.5"/> <!-- TODO: Tune -->
<dynamics friction="0.0" damping="0.5"/>
<xacro:insert_block name="safety_controller" />
</joint>

<link name="${name}_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.05" />
<mass value="0.05" />
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> <!--To stabilize simulation-->
</inertial>
<visual>
Expand Down
14 changes: 7 additions & 7 deletions urdf/fingers.urdf.xacro
Expand Up @@ -17,14 +17,14 @@
<!--Constants-->
<xacro:property name="thumb_abd_min" value="${ 0 * deg_to_rad}" />
<xacro:property name="thumb_abd_max" value="${ 90 * deg_to_rad}" />
<xacro:property name="finger_abd_min" value="${-30 * deg_to_rad}" /> <!--TODO: Check-->
<xacro:property name="finger_abd_max" value="${ 30 * deg_to_rad}" /> <!--TODO: Check-->
<xacro:property name="finger_abd_min" value="${-30 * deg_to_rad}" />
<xacro:property name="finger_abd_max" value="${ 30 * deg_to_rad}" />
<xacro:property name="finger_flex_min" value="${ 0 * deg_to_rad}" />
<xacro:property name="finger_flex_max" value="${ 45 * deg_to_rad}" />
<xacro:property name="finger_max_vel" value="2.0" /> <!--TODO: Check-->
<xacro:property name="finger_max_eff" value="2.0" /> <!--TODO: Check-->
<xacro:property name="finger_friction" value="0.0" /> <!--TODO: Check-->
<xacro:property name="finger_damping" value="0.5" /> <!--TODO: Check-->
<xacro:property name="finger_max_vel" value="2.0" />
<xacro:property name="finger_max_eff" value="2.0" />
<xacro:property name="finger_friction" value="0.0" />
<xacro:property name="finger_damping" value="0.5" />

<xacro:property name="finger_d1" value="0.009" />
<xacro:property name="finger_d2" value="0.013" />
Expand Down Expand Up @@ -225,7 +225,7 @@
<link name="${name}_link">
<inertial>
<origin xyz="${finger_d2 / 2.0} 0 0" rpy="0 0 0" />
<mass value="0.01" /> <!--TODO: can we make it zero and still have a stable dynamic simulation?-->
<mass value="0.01" />
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> <!-- To stabilize simulation -->
</inertial>
<visual>
Expand Down
1 change: 0 additions & 1 deletion urdf/palm.urdf.xacro
Expand Up @@ -29,7 +29,6 @@
<link name="${name}_link">
<inertial>
<origin xyz="0.0641 -0.0022 0.0021" rpy="0 0 0" />
<!-- NOTE: Less than total palm mass of 0.598kg because actuator masses are specified separately -->
<mass value="0.4" />
<inertia ixx="0.000305100" ixy="0.000005037" ixz="0.000015302"
iyy="0.000811920" iyz="0.000007622" izz="0.000655851" />
Expand Down

0 comments on commit 64777fc

Please sign in to comment.