Change hardware interface of mimetic joints to PositionJointInterface.
authorWalter Fetter Lages <w.fetter@ieee.org>
Sun, 5 May 2019 04:58:05 +0000 (01:58 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Sun, 5 May 2019 04:58:05 +0000 (01:58 -0300)
miitzhand_bringup/config/miitzhand.yaml
miitzhand_bringup/launch/gazebo.launch
miitzhand_description/urdf/miitzhand.urdf

index 8aa038e..a80da35 100644 (file)
@@ -7,29 +7,29 @@ miitzhand:
     thumb1_controller:
         type: effort_controllers/JointPositionController
         joint: thumb_j1 
-        pid: {p: 1, i: 0, d: 0}
+        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
 
     thumb2_controller:
         type: effort_controllers/JointPositionController
         joint: thumb_j2
-        pid: {p: 1, i: 0, d: 0}
+        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
 
     index_controller:
         type: effort_controllers/JointPositionController
         joint: index_j1
-        pid: {p: 1, i: 0, d: 0}
+        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
 
     middle_controller:
         type: effort_controllers/JointPositionController
-        joint: middle_j1 
-        pid: {p: 1, i: 0, d: 0}
+        joint: middle_j1
+        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
 
     ring_controller:
         type: effort_controllers/JointPositionController
         joint: ring_j1
-        pid: {p: 1, i: 0, d: 0}
+        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
 
     little_controller:
         type: effort_controllers/JointPositionController
         joint: little_j1
-        pid: {p: 1, i: 0, d: 0}
+        pid: {p: 0, i: 0, d: 0, i_clamp: 1.97, antiwindup: false, publish_state: true}
index ef177f2..6e76883 100644 (file)
@@ -20,7 +20,7 @@
         <!-- Spawn the robot model -->
         <node name="miitzhand_spawner" pkg="gazebo_ros" type="spawn_model" output="screen" 
               args="-urdf -param robot_description -model miitzhand
-               -J thum_j1 0 -J thumb_j2 -1.5708 -J index_j1 -1.5708
+               -J thumb_j1 0 -J thumb_j2 -1.5708 -J index_j1 -1.5708
                -J middle_j1 -1.5708 -J ring_j1 -1.5708 -J little_j1 -1.5708" />
       
         <!-- Controllers Settings-->
         <node name="controller_spawner" pkg="controller_manager" type="spawner"
             respawn="false" output="screen" ns="/miitzhand"
             args="
-            joint_state_controller  
+            joint_state_controller
             thumb1_controller
             thumb2_controller
             index_controller
             middle_controller
             ring_controller
             little_controller
-            --timeout 60">
-        </node>
-             
+            --timeout=60" />
 </launch>
index 03d030a..b65ec27 100644 (file)
@@ -75,7 +75,7 @@
  </link>
 
   <!-- 
-       It appears that Gazebo do not recognize joints in which the parent
+       It appears that Gazebo does not recognize joints in which the parent
        link does not have inertial properties. Hence attach litte_l1
        directly to base_link and not to little_l0.
   -->
@@ -87,7 +87,7 @@
     <limit lower="-3.14" upper="-1.57" effort="1.968989" velocity="5.61" />
     <dynamics damping="0.336538" friction="0.075478" />
   </joint>
-
  <link name="little_l2">
     <inertial>
       <origin xyz="0.010872 0.00039672 4.7668E-06" rpy="0 0 0" />
     </collision>
  </link>
 
-  <!-- 
-       It appears that Gazebo do not recognize joints in which the parent
+  <!--
+       It appears that Gazebo does not recognize joints in which the parent
        link does not have inertial properties. Hence attach ring_l1
        directly to base_link and not to ring_l0.
   -->
     </collision>
  </link>
 
-  <!-- 
-       It appears that Gazebo do not recognize joints in which the parent
+  <!--
+       It appears that Gazebo does not recognize joints in which the parent
        link does not have inertial properties. Hence attach middle_l1
        directly to base_link and not to middle_l0.
   -->
  </link>
 
   <!-- 
-       It appears that Gazebo do not recognize joints in which the parent
+       It appears that Gazebo does not recognize joints in which the parent
        link does not have inertial properties. Hence attach index_l1
        directly to base_link and not to index_l0.
   -->
  </link>
 
   <!-- 
-       It appears that Gazebo do not recognize joints in which the parent
+       It appears that Gazebo does not recognize joints in which the parent
        link does not have inertial properties. Hence attach thumb_l1
        directly to base_link and not to thumb_l0.
   -->
     <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-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>
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
+
 <transmission name="thumb2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="thumb_j2">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
+
 <transmission name="thumb3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="thumb_j3">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+               <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>    
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <transmission name="index1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="index_j1">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
         </joint>    
         <actuator name="index1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
+
 <transmission name="index2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="index_j2">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
         </joint>    
         <actuator name="index2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
        <mimicJoint>index_j1</mimicJoint>    
        <multiplier>1.0</multiplier>    
        <offset>1.57</offset>
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <transmission name="index3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="index_j3">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
         </joint>    
         <actuator name="index3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
        <mimicJoint>index_j1</mimicJoint>    
        <multiplier>1.0</multiplier>    
        <offset>1.57</offset>
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <transmission name="middle1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="middle_j1">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
         </joint>    
         <actuator name="middle1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
+
 <transmission name="middle2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="middle_j2">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
         </joint>    
         <actuator name="middle2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
        <mimicJoint>middle_j1</mimicJoint>    
        <multiplier>1.0</multiplier>    
        <offset>1.57</offset>
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <transmission name="middle3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="middle_j3">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
         </joint>    
         <actuator name="middle3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
        <mimicJoint>middle_j1</mimicJoint>    
        <multiplier>1.0</multiplier>    
        <offset>1.57</offset>
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <transmission name="ring1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="ring_j1">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
         </joint>    
         <actuator name="ring1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
+
 <transmission name="ring2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="ring_j2">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
         </joint>    
         <actuator name="ring2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
        <mimicJoint>ring_j1</mimicJoint>    
        <multiplier>1.0</multiplier>    
        <offset>1.57</offset>
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <transmission name="ring3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="ring_j3">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
         </joint>    
         <actuator name="ring3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
        <mimicJoint>ring_j1</mimicJoint>    
        <multiplier>1.0</multiplier>    
        <offset>1.57</offset>
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <transmission name="little1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="little_j1">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
         </joint>    
         <actuator name="little1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
         </actuator>    
 </transmission>    
-    
+
 <transmission name="little2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="little_j2">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
         </joint>    
         <actuator name="little2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
        <mimicJoint>little_j1</mimicJoint>    
        <multiplier>1.0</multiplier>    
        <offset>1.57</offset>
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <transmission name="little3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="little_j3">    
-                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
         </joint>    
         <actuator name="little3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
        <mimicJoint>little_j1</mimicJoint>    
        <multiplier>1.0</multiplier>    
        <offset>1.57</offset>
-       <maxEffort>30.0</maxEffort>    
+       <maxEffort>1.968989</maxEffort>
        <sensitiveness>0.0</sensitiveness>    
   </plugin>    
 </gazebo>    
-    
+
 <gazebo>    
     <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">    
        <robotNamespace>/miitzhand</robotNamespace>