From: Walter Fetter Lages Date: Mon, 6 May 2019 04:07:27 +0000 (-0300) Subject: Change controller gains. Change max integration step to 30us. X-Git-Tag: sbai2019submitted~2 X-Git-Url: http://git.ece.ufrgs.br/?a=commitdiff_plain;h=d641cee5d1a76e9f17e9bcaf16eab8beb21058dd;p=users%2Fgschmitz%2Fmiitzhand.git Change controller gains. Change max integration step to 30us. --- diff --git a/miitzhand_bringup/config/miitzhand.yaml b/miitzhand_bringup/config/miitzhand.yaml index a80da35..72636e8 100644 --- a/miitzhand_bringup/config/miitzhand.yaml +++ b/miitzhand_bringup/config/miitzhand.yaml @@ -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} diff --git a/miitzhand_bringup/launch/gazebo.launch b/miitzhand_bringup/launch/gazebo.launch index 6e76883..5d857eb 100644 --- a/miitzhand_bringup/launch/gazebo.launch +++ b/miitzhand_bringup/launch/gazebo.launch @@ -11,9 +11,9 @@ - + - + diff --git a/miitzhand_bringup/worlds/empty_30us.world b/miitzhand_bringup/worlds/empty_30us.world new file mode 100644 index 0000000..d966887 --- /dev/null +++ b/miitzhand_bringup/worlds/empty_30us.world @@ -0,0 +1,23 @@ + + + + + + + 12 + + + + + + model://sun + + + + model://ground_plane + + + 0.00003 + + + diff --git a/miitzhand_description/urdf/miitzhand.urdf b/miitzhand_description/urdf/miitzhand.urdf index b65ec27..17a233c 100644 --- a/miitzhand_description/urdf/miitzhand.urdf +++ b/miitzhand_description/urdf/miitzhand.urdf @@ -552,8 +552,11 @@ - - + + + + @@ -617,46 +620,46 @@ - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - 1.87 - - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - 1.87 - - - - - transmission_interface/SimpleTransmission - + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1.87 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1.87 + + + + + transmission_interface/SimpleTransmission + hardware_interface/PositionJointInterface - - - 1.87 - - - - - - thumb_j3 - thumb_j2 - 1.0 - 1.57 + + + 1.87 + + + + + + thumb_j2 + thumb_j3 + 1.0 + 1.57 1.968989 - 0.0 - - + 0.0 + + transmission_interface/SimpleTransmission @@ -677,17 +680,17 @@ 1.87 - + - index_j2 - index_j1 - 1.0 + index_j1 + index_j2 + 1.0 1.57 1.968989 - 0.0 - - + 0.0 + + transmission_interface/SimpleTransmission @@ -698,17 +701,17 @@ 1.87 - - - - index_j3 - index_j1 - 1.0 + + + + index_j1 + index_j3 + 1.0 1.57 1.968989 - 0.0 - - + 0.0 + + transmission_interface/SimpleTransmission @@ -730,16 +733,16 @@ - - - middle_j2 - middle_j1 - 1.0 + + + middle_j1 + middle_j2 + 1.0 1.57 1.968989 - 0.0 - - + 0.0 + + transmission_interface/SimpleTransmission @@ -751,16 +754,16 @@ - - - middle_j3 - middle_j1 - 1.0 + + + middle_j1 + middle_j3 + 1.0 1.57 1.968989 - 0.0 - - + 0.0 + + transmission_interface/SimpleTransmission @@ -781,17 +784,17 @@ 1.87 - - - - ring_j2 - ring_j1 - 1.0 + + + + ring_j1 + ring_j2 + 1.0 1.57 1.968989 - 0.0 - - + 0.0 + + transmission_interface/SimpleTransmission @@ -802,17 +805,17 @@ 1.87 - - - - ring_j3 - ring_j1 - 1.0 + + + + ring_j1 + ring_j3 + 1.0 1.57 1.968989 - 0.0 - - + 0.0 + + transmission_interface/SimpleTransmission @@ -833,17 +836,17 @@ 1.87 - - - - little_j2 - little_j1 - 1.0 + + + + little_j1 + little_j2 + 1.0 1.57 1.968989 - 0.0 - - + 0.0 + + transmission_interface/SimpleTransmission @@ -854,24 +857,24 @@ 1.87 - - - - little_j3 - little_j1 - 1.0 + + + + little_j1 + little_j3 + 1.0 1.57 1.968989 - 0.0 - - + 0.0 + + - - - /miitzhand - 0.001 - gazebo_ros_control/DefaultRobotHWSim - + + + /miitzhand + 0.001 + gazebo_ros_control/DefaultRobotHWSim +