Tuned a little bit the PIDs

This commit is contained in:
Konstantinos Chatzilygeroudis 2014-06-02 22:06:00 +03:00
parent e698191e20
commit 8346b234ef
2 changed files with 30 additions and 30 deletions

View File

@ -1,52 +1,52 @@
nao_dcm/gazebo_ros_control/pid_gains: nao_dcm/gazebo_ros_control/pid_gains:
HeadYaw: {p: 60.0, i: 80.0, d: 0.3} HeadYaw: {p: 1000.0, i: 0.0, d: 0.0}
HeadPitch: {p: 60.0, i: 80.0, d: 0.3} HeadPitch: {p: 1000.0, i: 0.0, d: 0.0}
LShoulderPitch: {p: 60.0, i: 80.0, d: 0.3} LShoulderPitch: {p: 5000.0, i: 0.0, d: 0.0}
LElbowYaw: {p: 60.0, i: 80.0, d: 0.3} LElbowYaw: {p: 100.0, i: 0.0, d: 0.0}
LElbowRoll: {p: 60.0, i: 80.0, d: 0.3} LElbowRoll: {p: 100.0, i: 0.0, d: 0.0}
LShoulderRoll: {p: 60.0, i: 80.0, d: 0.3} LShoulderRoll: {p: 5000.0, i: 0.0, d: 0.0}
LWristYaw: {p: 60.0, i: 80.0, d: 0.3} LWristYaw: {p: 20.0, i: 0.0, d: 0.0}
LHand: {p: 60.0, i: 80.0, d: 0.3} LHand: {p: 1.0, i: 0.0, d: 0.0}
RShoulderPitch: {p: 60.0, i: 80.0, d: 0.3} RShoulderPitch: {p: 5000.0, i: 0.0, d: 0.0}
RElbowYaw: {p: 60.0, i: 80.0, d: 0.3} RElbowYaw: {p: 100.0, i: 0.0, d: 0.0}
RElbowRoll: {p: 60.0, i: 80.0, d: 0.3} RElbowRoll: {p: 100.0, i: 0.0, d: 0.0}
RShoulderRoll: {p: 60.0, i: 80.0, d: 0.3} RShoulderRoll: {p: 5000.0, i: 0.0, d: 0.0}
RWristYaw: {p: 60.0, i: 80.0, d: 0.3} RWristYaw: {p: 20.0, i: 0.0, d: 0.0}
RHand: {p: 60.0, i: 80.0, d: 0.3} RHand: {p: 1.0, i: 0.0, d: 0.0}
LHipYawPitch: {p: 60.0, i: 80.0, d: 0.3} LHipYawPitch: {p: 1000.0, i: 0.0, d: 0.0}
LHipRoll: {p: 60.0, i: 80.0, d: 0.3} LHipRoll: {p: 1000.0, i: 0.0, d: 0.0}
LHipPitch: {p: 60.0, i: 80.0, d: 0.3} LHipPitch: {p: 1000.0, i: 0.0, d: 0.0}
LKneePitch: {p: 60.0, i: 80.0, d: 0.3} LKneePitch: {p: 1000.0, i: 0.0, d: 0.0}
LAnklePitch: {p: 60.0, i: 80.0, d: 0.3} LAnklePitch: {p: 1000.0, i: 0.0, d: 0.0}
LAnkleRoll: {p: 60.0, i: 80.0, d: 0.3} LAnkleRoll: {p: 1000.0, i: 0.0, d: 0.0}
RHipYawPitch: {p: 60.0, i: 80.0, d: 0.3} RHipYawPitch: {p: 1000.0, i: 0.0, d: 0.0}
RHipRoll: {p: 60.0, i: 80.0, d: 0.3} RHipRoll: {p: 1000.0, i: 0.0, d: 0.0}
RHipPitch: {p: 60.0, i: 80.0, d: 0.3} RHipPitch: {p: 1000.0, i: 0.0, d: 0.0}
RKneePitch: {p: 60.0, i: 80.0, d: 0.3} RKneePitch: {p: 1000.0, i: 0.0, d: 0.0}
RAnklePitch: {p: 60.0, i: 80.0, d: 0.3} RAnklePitch: {p: 1000.0, i: 0.0, d: 0.0}
RAnkleRoll: {p: 60.0, i: 80.0, d: 0.3} RAnkleRoll: {p: 1000.0, i: 0.0, d: 0.0}

View File

@ -88,12 +88,12 @@
<alwaysOn>true</alwaysOn> <alwaysOn>true</alwaysOn>
</plugin> </plugin>
<!-- Mimic joints through plugin develop by costashatz based on implementation by Goncalo Cabrita --> <!-- Mimic joints through plugin develop by costashatz based on implementation by Goncalo Cabrita -->
<plugin name="mimic_hipyawpitch" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so"> <!-- <plugin name="mimic_hipyawpitch" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
<joint>LHipYawPitch</joint> <joint>LHipYawPitch</joint>
<mimicJoint>RHipYawPitch</mimicJoint> <mimicJoint>RHipYawPitch</mimicJoint>
<multiplier>1.0</multiplier> <multiplier>1.0</multiplier>
<offset>0.0</offset> <offset>0.0</offset>
</plugin> </plugin> -->
<xacro:FingerMimics side="L" num="1"/> <xacro:FingerMimics side="L" num="1"/>
<xacro:FingerMimics side="L" num="2"/> <xacro:FingerMimics side="L" num="2"/>
@ -363,7 +363,7 @@
<selfCollide>false</selfCollide> <selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff> <turnGravityOff>false</turnGravityOff>
<fdir1>1 0 0</fdir1> <fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel> <maxVel>0.1</maxVel>
<minDepth>0.003</minDepth> <minDepth>0.003</minDepth>
</gazebo> </gazebo>
<gazebo reference="RHipYaw"> <gazebo reference="RHipYaw">
@ -408,7 +408,7 @@
<selfCollide>false</selfCollide> <selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff> <turnGravityOff>false</turnGravityOff>
<fdir1>1 0 0</fdir1> <fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel> <maxVel>0.1</maxVel>
<minDepth>0.003</minDepth> <minDepth>0.003</minDepth>
</gazebo> </gazebo>
<!-- END OF GAZEBO MATERIALS --> <!-- END OF GAZEBO MATERIALS -->