Improved Gazebo a little more. Added argument to choose whether to include pids on the motors. Without the pids the motion is very good, but robot slides and in some cases the forces get extremely large. Also, fixed/tweaked values in URDF/xacro

This commit is contained in:
Konstantinos Chatzilygeroudis 2014-05-30 02:47:20 +03:00
parent 125dc32da4
commit 137c308606
3 changed files with 32 additions and 20 deletions

View File

@ -8,7 +8,13 @@
<arg name="paused" value="true"/>
<!-- more default parameters can be changed here -->
</include>
<rosparam file="$(find nao_dcm_gazebo)/config/gazebo_ros_control_params.yaml" command="load"/>
<!-- Use PIDs?? -->
<arg name="use_pid" value="false"/>
<group if="$(arg use_pid)">
<rosparam file="$(find nao_dcm_gazebo)/config/gazebo_ros_control_params.yaml" command="load"/>
</group>
<!-- Call Nao Robot Trajectory Controller -->
<include file="$(find nao_dcm_control)/launch/nao_dcm_trajectory_control_H21.launch"/>

View File

@ -8,7 +8,13 @@
<arg name="paused" value="true"/>
<!-- more default parameters can be changed here -->
</include>
<rosparam file="$(find nao_dcm_gazebo)/config/gazebo_ros_control_params.yaml" command="load"/>
<!-- Use PIDs?? -->
<arg name="use_pid" value="false"/>
<group if="$(arg use_pid)">
<rosparam file="$(find nao_dcm_gazebo)/config/gazebo_ros_control_params.yaml" command="load"/>
</group>
<!-- Call Nao Robot Trajectory Controller -->
<include file="$(find nao_dcm_control)/launch/nao_dcm_trajectory_control_H25.launch"/>

View File

@ -141,63 +141,63 @@
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="LFinger12">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="LFinger13">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="LFinger21">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="LFinger22">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="LFinger23">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="LThumb1">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="LThumb2">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="l_gripper">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="RShoulder">
<mu1>0.5</mu1>
@ -230,63 +230,63 @@
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="RFinger12">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="RFinger13">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="RFinger21">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="RFinger22">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="RFinger23">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="RThumb1">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="RThumb2">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="r_gripper">
<material>Gazebo/Yellow</material>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
<selfCollide>false</selfCollide>
<turnGravityOff>false</turnGravityOff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="LHipYaw">
<material>Gazebo/Green</material>