Change controller gains. Change max integration step to 30us.
authorWalter Fetter Lages <w.fetter@ieee.org>
Mon, 6 May 2019 04:07:27 +0000 (01:07 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Mon, 6 May 2019 04:07:27 +0000 (01:07 -0300)
miitzhand_bringup/config/miitzhand.yaml
miitzhand_bringup/launch/gazebo.launch
miitzhand_bringup/worlds/empty_30us.world [new file with mode: 0644]
miitzhand_description/urdf/miitzhand.urdf

index a80da35..72636e8 100644 (file)
@@ -2,34 +2,34 @@ miitzhand:
 
     joint_state_controller:
         type: joint_state_controller/JointStateController
-        publish_rate: 100
+        publish_rate: 1000
 
     thumb1_controller:
         type: effort_controllers/JointPositionController
-        joint: thumb_j1 
-        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
+        joint: thumb_j1
+        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     thumb2_controller:
         type: effort_controllers/JointPositionController
         joint: thumb_j2
-        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
+        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     index_controller:
         type: effort_controllers/JointPositionController
         joint: index_j1
-        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
+        pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     middle_controller:
         type: effort_controllers/JointPositionController
         joint: middle_j1
-        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
+        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     ring_controller:
         type: effort_controllers/JointPositionController
         joint: ring_j1
-        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
+        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
 
     little_controller:
         type: effort_controllers/JointPositionController
         joint: little_j1
-        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
+        pid: {p: 2.92, i: 16.70, d: 0.0, i_clamp: 1.96, antiwindup: true}
index 6e76883..5d857eb 100644 (file)
@@ -11,9 +11,9 @@
        <arg name="paused" value="$(arg paused)" />
        <arg name="use_sim_time" value="$(arg use_sim_time)"/>
        <arg name="headless" value="$(arg headless)"/>
-       <arg name="world_name" value="worlds/empty.world"/>
+       <arg name="world_name" value="$(find miitzhand_bringup)/worlds/empty_30us.world"/>
    </include>
-         
+
         <!-- Robot model -->
        <include file="$(find miitzhand_description)/launch/miitzhand.launch" />
         
diff --git a/miitzhand_bringup/worlds/empty_30us.world b/miitzhand_bringup/worlds/empty_30us.world
new file mode 100644 (file)
index 0000000..d966887
--- /dev/null
@@ -0,0 +1,23 @@
+<?xml version="1.0" ?>
+<sdf version="1.5">
+  <world name="default">
+    <scene>
+      <sky>
+        <clouds>
+          <speed>12</speed>
+        </clouds>
+      </sky>
+    </scene>
+    <!-- A global light source -->
+    <include>
+      <uri>model://sun</uri>
+    </include>
+    <!-- A ground plane -->
+    <include>
+      <uri>model://ground_plane</uri>
+    </include>
+    <physics type="ode">
+      <max_step_size>0.00003</max_step_size>
+    </physics>
+  </world>
+</sdf>
index b65ec27..17a233c 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" />
+
+      <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>
     <mimic joint="thumb_j2" multiplier="1" offset="1.57" />
   </joint>
 
-<transmission name="thumb1_transmission">    
-        <type>transmission_interface/SimpleTransmission</type>    
-        <joint name="thumb_j1">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
-        </joint>    
-        <actuator name="thumb1_motor">    
-                <mechanicalReduction>1.87</mechanicalReduction>    
-        </actuator>    
-</transmission>    
-
-<transmission name="thumb2_transmission">    
-        <type>transmission_interface/SimpleTransmission</type>    
-        <joint name="thumb_j2">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
-        </joint>    
-        <actuator name="thumb2_motor">    
-                <mechanicalReduction>1.87</mechanicalReduction>    
-        </actuator>    
-</transmission>    
-
-<transmission name="thumb3_transmission">    
-        <type>transmission_interface/SimpleTransmission</type>    
-        <joint name="thumb_j3">    
+<transmission name="thumb1_transmission">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="thumb_j1">
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="thumb1_motor">
+                <mechanicalReduction>1.87</mechanicalReduction>
+        </actuator>
+</transmission>
+
+<transmission name="thumb2_transmission">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="thumb_j2">
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="thumb2_motor">
+                <mechanicalReduction>1.87</mechanicalReduction>
+        </actuator>
+</transmission>
+
+<transmission name="thumb3_transmission">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="thumb_j3">
                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
-        </joint>    
-        <actuator name="thumb3_motor">    
-                <mechanicalReduction>1.87</mechanicalReduction>    
-        </actuator>    
-</transmission>    
-
-<gazebo>    
-  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>thumb_j3</joint>    
-       <mimicJoint>thumb_j2</mimicJoint>    
-       <multiplier>1.0</multiplier>    
-       <offset>1.57</offset>    
+        </joint>
+        <actuator name="thumb3_motor">
+                <mechanicalReduction>1.87</mechanicalReduction>
+        </actuator>
+</transmission>
+
+<gazebo>
+  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
+       <joint>thumb_j2</joint>
+       <mimicJoint>thumb_j3</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
 <transmission name="index1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
+
 <gazebo>    
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>index_j2</joint>    
-       <mimicJoint>index_j1</mimicJoint>    
-       <multiplier>1.0</multiplier>    
+       <joint>index_j1</joint>
+       <mimicJoint>index_j2</mimicJoint>
+       <multiplier>1.0</multiplier>
        <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
 <transmission name="index3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
-<gazebo>    
-  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>index_j3</joint>    
-       <mimicJoint>index_j1</mimicJoint>    
-       <multiplier>1.0</multiplier>    
+
+<gazebo>
+  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
+       <joint>index_j1</joint>
+       <mimicJoint>index_j3</mimicJoint>
+       <multiplier>1.0</multiplier>
        <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
 <transmission name="middle1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         </actuator>    
 </transmission>    
     
-<gazebo>    
-  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>middle_j2</joint>    
-       <mimicJoint>middle_j1</mimicJoint>    
-       <multiplier>1.0</multiplier>    
+<gazebo>
+  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
+       <joint>middle_j1</joint>
+       <mimicJoint>middle_j2</mimicJoint>
+       <multiplier>1.0</multiplier>
        <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
 <transmission name="middle3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         </actuator>    
 </transmission>    
     
-<gazebo>    
-  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>middle_j3</joint>    
-       <mimicJoint>middle_j1</mimicJoint>    
-       <multiplier>1.0</multiplier>    
+<gazebo>
+  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
+       <joint>middle_j1</joint>
+       <mimicJoint>middle_j3</mimicJoint>
+       <multiplier>1.0</multiplier>
        <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
 <transmission name="ring1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
-<gazebo>    
-  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>ring_j2</joint>    
-       <mimicJoint>ring_j1</mimicJoint>    
-       <multiplier>1.0</multiplier>    
+
+<gazebo>
+  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
+       <joint>ring_j1</joint>
+       <mimicJoint>ring_j2</mimicJoint>
+       <multiplier>1.0</multiplier>
        <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
 <transmission name="ring3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
-<gazebo>    
-  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>ring_j3</joint>    
-       <mimicJoint>ring_j1</mimicJoint>    
-       <multiplier>1.0</multiplier>    
+
+<gazebo>
+  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
+       <joint>ring_j1</joint>
+       <mimicJoint>ring_j3</mimicJoint>
+       <multiplier>1.0</multiplier>
        <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
 <transmission name="little1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
-<gazebo>    
-  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>little_j2</joint>    
-       <mimicJoint>little_j1</mimicJoint>    
-       <multiplier>1.0</multiplier>    
+
+<gazebo>
+  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
+       <joint>little_j1</joint>
+       <mimicJoint>little_j2</mimicJoint>
+       <multiplier>1.0</multiplier>
        <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
 <transmission name="little3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
-<gazebo>    
-  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">    
-       <joint>little_j3</joint>    
-       <mimicJoint>little_j1</mimicJoint>    
-       <multiplier>1.0</multiplier>    
+
+<gazebo>
+  <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
+       <joint>little_j1</joint>
+       <mimicJoint>little_j3</mimicJoint>
+       <multiplier>1.0</multiplier>
        <offset>1.57</offset>
        <maxEffort>1.968989</maxEffort>
-       <sensitiveness>0.0</sensitiveness>    
-  </plugin>    
-</gazebo>    
+       <sensitiveness>0.0</sensitiveness>
+  </plugin>
+</gazebo>
 
-<gazebo>    
-    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">    
-       <robotNamespace>/miitzhand</robotNamespace>    
-       <controlPeriod>0.001</controlPeriod>    
-       <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>    
-    </plugin>    
+<gazebo>
+    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
+       <robotNamespace>/miitzhand</robotNamespace>
+       <controlPeriod>0.001</controlPeriod>
+       <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
+    </plugin>
 </gazebo>
 
 </robot>