Fix gains for thumb controllers.
authorWalter Fetter Lages <w.fetter@ieee.org>
Mon, 6 May 2019 05:44:49 +0000 (02:44 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Mon, 6 May 2019 05:44:49 +0000 (02:44 -0300)
miitzhand_bringup/config/miitzhand.yaml
miitzhand_description/urdf/miitzhand.urdf

index 72636e8..2961601 100644 (file)
@@ -7,12 +7,12 @@ miitzhand:
     thumb1_controller:
         type: effort_controllers/JointPositionController
         joint: thumb_j1
-        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
+        pid: {p: 29.4, i: 1640, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     thumb2_controller:
         type: effort_controllers/JointPositionController
         joint: thumb_j2
-        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
+        pid: {p: 29.2, i: 1680, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     index_controller:
         type: effort_controllers/JointPositionController
@@ -22,14 +22,14 @@ miitzhand:
     middle_controller:
         type: effort_controllers/JointPositionController
         joint: middle_j1
-        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
+        pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     ring_controller:
         type: effort_controllers/JointPositionController
         joint: ring_j1
-        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
+        pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     little_controller:
         type: effort_controllers/JointPositionController
         joint: little_j1
-        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
+        pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
index 17a233c..33c2261 100644 (file)
     <inertial>
       <origin xyz="0.021926 0.00020302 9.7353E-08" rpy="0 0 0" />
       <mass value="0.010346" />
-
       <inertia ixx="4.6802E-07" ixy="5.726E-08" ixz="1.5393E-11" iyy="2.4622E-06" iyz="4.7897E-11" izz="2.4327E-06" />
-
-      <!--inertia ixx="4.6802E-04" ixy="5.726E-08" ixz="1.5393E-11" iyy="2.4622E-04" iyz="4.7897E-11" izz="2.4327E-04"
-/-->
     </inertial>
 
     <visual>