From cc919a2c3916f5231f24e53647c719cecb9e1439 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Sergi=20Hern=C3=A1ndez?= <shernand@iri.upc.edu>
Date: Mon, 6 Jun 2016 22:24:55 +0200
Subject: [PATCH] Solved an orientation error in one of the obstacles of the
 vision environment. Changes to be able to use a different robot by providing
 its name. Chnages to allow the obstacles to move freely. Still not working.

---
 ...cm510_control.yaml => bioloid_ceabot.yaml} |  0
 .../launch/bioloid_cm510_control.launch       |  3 ++-
 .../launch/bioloid_cm510_sim.launch           |  1 +
 .../urdf/ceabot/obstacle.xacro                | 21 +++++++++++++++++--
 .../urdf/ceabot/vision_env.xacro              |  2 +-
 5 files changed, 23 insertions(+), 4 deletions(-)
 rename bioloid_control/config/{bioloid_cm510_control.yaml => bioloid_ceabot.yaml} (100%)

diff --git a/bioloid_control/config/bioloid_cm510_control.yaml b/bioloid_control/config/bioloid_ceabot.yaml
similarity index 100%
rename from bioloid_control/config/bioloid_cm510_control.yaml
rename to bioloid_control/config/bioloid_ceabot.yaml
diff --git a/bioloid_control/launch/bioloid_cm510_control.launch b/bioloid_control/launch/bioloid_cm510_control.launch
index 40e308b..a8d343c 100644
--- a/bioloid_control/launch/bioloid_cm510_control.launch
+++ b/bioloid_control/launch/bioloid_cm510_control.launch
@@ -1,9 +1,10 @@
 <launch>
 
   <arg name="mtn_file" default="bio_prm_humanoidtypea_en" />
+  <arg name="robot" default="bioloid_ceabot" />
 
   <!-- Load joint controller configurations from YAML file to parameter server -->
-  <rosparam file="$(find bioloid_control)/config/bioloid_cm510_control.yaml" command="load"/>
+  <rosparam file="$(find bioloid_control)/config/$(arg robot).yaml" command="load"/>
 
   <param name="motions_file" value="$(find bioloid_controller_cm510)/motions/$(arg mtn_file).mtn"/>
 
diff --git a/bioloid_description/launch/bioloid_cm510_sim.launch b/bioloid_description/launch/bioloid_cm510_sim.launch
index 286663b..b0bfa7b 100644
--- a/bioloid_description/launch/bioloid_cm510_sim.launch
+++ b/bioloid_description/launch/bioloid_cm510_sim.launch
@@ -9,6 +9,7 @@
 
   <include file="$(find bioloid_control)/launch/bioloid_cm510_control.launch">
     <arg name="mtn_file" value="$(arg mtn_file)"/>
+    <arg name="robot" value="$(arg robot)"/>
   </include>
 
 </launch>
diff --git a/bioloid_description/urdf/ceabot/obstacle.xacro b/bioloid_description/urdf/ceabot/obstacle.xacro
index e16aea1..d6b8eb2 100644
--- a/bioloid_description/urdf/ceabot/obstacle.xacro
+++ b/bioloid_description/urdf/ceabot/obstacle.xacro
@@ -26,7 +26,7 @@
       </collision>
     </link>
 
-    <joint name="${name}_joint" type="fixed">
+    <joint name="${name}_joint" type="floating">
       <origin xyz="${grid_x*0.25+0.13} ${grid_y*0.25+0.63} 0" rpy="1.5707 0 0"/>
       <parent link="${parent}_link"/>
       <child link="${name}_link"/>
@@ -46,10 +46,27 @@
 
     <xacro:qrcode name="${name}_east" parent="${name}" code="${east_code}">
       <origin xyz="-0.126 0.375 0.0" rpy="3.14159 0 -1.5707" />
-    </xacro:qrcode>-->
+    </xacro:qrcode>
 
     <gazebo reference="${name}_link">
+      <gravity>true</gravity>
+      <selfCollide>false</selfCollide>
+      <maxContacts>10</maxContacts>
+      <dampingFactor>0.2</dampingFactor>
+      <maxVel>0.0</maxVel>
+      <minDepth>0.0</minDepth>
+      <mu1>0.200000</mu1>
+      <mu2>0.200000</mu2>
+      <kp>0.0</kp>
+      <kd>0.0</kd>
+    </gazebo>
+
+    <gazebo reference="${name}_joint">
+      <implicitSpringDamper>true</implicitSpringDamper>
+      <stopCfm>0.0</stopCfm>
+      <stopErp>0.0</stopErp>
     </gazebo>
+
   </xacro:macro>
 </root>
 
diff --git a/bioloid_description/urdf/ceabot/vision_env.xacro b/bioloid_description/urdf/ceabot/vision_env.xacro
index f792a68..39b8d7b 100755
--- a/bioloid_description/urdf/ceabot/vision_env.xacro
+++ b/bioloid_description/urdf/ceabot/vision_env.xacro
@@ -10,7 +10,7 @@
   <xacro:obstacle_vis name="obstacle1" parent="obstacle_base" center_x="1.015" center_y="1.265" distance="0.75" angle="0" cosine="1" sine="0" code="turn_right_45"/>
   <xacro:obstacle_vis name="obstacle2" parent="obstacle_base" center_x="1.015" center_y="1.265" distance="0.75" angle="0.79" cosine="0.707" sine="0.707" code="turn_left_180"/>
   <xacro:obstacle_vis name="obstacle3" parent="obstacle_base" center_x="1.015" center_y="1.265" distance="0.75" angle="3.14159" cosine="-1" sine="0" code="turn_right_45"/>
-  <xacro:obstacle_vis name="obstacle4" parent="obstacle_base" center_x="1.015" center_y="1.265" distance="0.75" angle="3.93" cosine="-0.707" sine="0.707" code="turn_right_90"/>
+  <xacro:obstacle_vis name="obstacle4" parent="obstacle_base" center_x="1.015" center_y="1.265" distance="0.75" angle="3.93" cosine="-0.707" sine="-0.707" code="turn_right_90"/>
   <xacro:obstacle_vis name="obstacle5" parent="obstacle_base" center_x="1.015" center_y="1.265" distance="0.75" angle="4.71" cosine="0" sine="-1" code="turn_right_180"/>
   
 </robot>
-- 
GitLab