From 1da5010f68c9b6d531fb55ef4f772a470747361c Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Sergi=20Hern=C3=A1ndez?= <shernand@iri.upc.edu>
Date: Mon, 16 May 2016 23:36:18 +0200
Subject: [PATCH] Added the walk ready action for fast motions. Changed the
 simulation parameters (max joint speed and torque) to improve the simulation.
 (They do not coincide with the real robot). Reduced the minimum simulation
 step to improve the simulation. Added a gazebo file for the bioloid_ceabot
 robot.

---
 .../config/bioloid_cm510_control.yaml         |  80 +++----
 .../include/bioloid_controller_cm510_impl.h   |   2 +-
 .../motions/ceabot_motions.mtn                |   7 +-
 bioloid_description/urdf/bioloid.gazebo       | 196 ++++++++++++++++--
 bioloid_description/urdf/bioloid.xacro        |  36 ++--
 .../urdf/bioloid_ceabot.gazebo                |  49 +++++
 bioloid_description/urdf/bioloid_ceabot.xacro |   3 +-
 bioloid_gazebo/worlds/bioloid.world           |   4 +-
 8 files changed, 289 insertions(+), 88 deletions(-)
 create mode 100644 bioloid_description/urdf/bioloid_ceabot.gazebo

diff --git a/bioloid_control/config/bioloid_cm510_control.yaml b/bioloid_control/config/bioloid_cm510_control.yaml
index f744acf..bc3cf29 100644
--- a/bioloid_control/config/bioloid_cm510_control.yaml
+++ b/bioloid_control/config/bioloid_cm510_control.yaml
@@ -44,141 +44,141 @@ bioloid:
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_high_arm_l:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_low_arm_l:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_shoulder_r:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_high_arm_r:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_low_arm_r:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_pelvis_yaw_l:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_pelvis_roll_l:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_pelvis_pitch_l:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_knee_l:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_ankle_pitch_l:
-        p: 8.0
+        p: 4.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_ankle_roll_l:
-        p: 8.0
+        p: 4.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_pelvis_yaw_r:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_pelvis_roll_r:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_pelvis_pitch_r:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_knee_r:
         p: 8.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_ankle_pitch_r:
-        p: 8.0
+        p: 4.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
       j_ankle_roll_r:
-        p: 8.0
+        p: 4.0
         d: 0.0
         i: 0.0
         proxy:
           lambda: 3.0
-          vel_limit: 6.0
-          effort_limit: 1.5
+          vel_limit: 12.0
+          effort_limit: 2.5
diff --git a/bioloid_controller_cm510/include/bioloid_controller_cm510_impl.h b/bioloid_controller_cm510/include/bioloid_controller_cm510_impl.h
index b05c28d..1d0f8fa 100644
--- a/bioloid_controller_cm510/include/bioloid_controller_cm510_impl.h
+++ b/bioloid_controller_cm510/include/bioloid_controller_cm510_impl.h
@@ -343,7 +343,7 @@ namespace bioloid_controller_cm510
       for (unsigned int i = 0; i < this->joints_.size(); ++i)
       {
         target_angles[i] = ((((manager_servos[i].current_value+balance_offsets[i]-manager_servos[i].center_value)*300.0/1023.0)*3.14159)/180.0);
-        const double command = pids_[i]->computeCommand(target_angles[i]-real_angles[i],period);
+        const double command = this->pids_[i]->computeCommand(target_angles[i]-real_angles[i],period);
         this->joints_[i].setCommand(command);
       }
     }
diff --git a/bioloid_controller_cm510/motions/ceabot_motions.mtn b/bioloid_controller_cm510/motions/ceabot_motions.mtn
index 707e37e..645cf62 100755
--- a/bioloid_controller_cm510/motions/ceabot_motions.mtn
+++ b/bioloid_controller_cm510/motions/ceabot_motions.mtn
@@ -238,9 +238,10 @@ compliance=5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5
 play_param=0 0 1 1.0 32
 page_end
 page_begin
-name=
-compliance=5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5
-play_param=0 0 1 1.0 32
+name=Fst_Ready
+compliance=5 7 7 5 5 5 5 5 5 5 5 5 5 5 5 6 6 6 6 5 5 5 5 5 5 5
+play_param=0 0 1 1.0 5
+step=512 235 788 279 744 462 561 358 666 507 516 301 722 170 853 687 336 507 516 512 512 512 512 512 512 512 0.000 1.000
 page_end
 page_begin
 name=Walk_Ready
diff --git a/bioloid_description/urdf/bioloid.gazebo b/bioloid_description/urdf/bioloid.gazebo
index 3acde0e..634f329 100644
--- a/bioloid_description/urdf/bioloid.gazebo
+++ b/bioloid_description/urdf/bioloid.gazebo
@@ -82,207 +82,357 @@
 
   <gazebo reference="base_link">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_shoulder">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_arm_high">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_arm_low">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="right_shoulder">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="right_arm_high">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="right_arm_low">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_leg_pelvis_yaw">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_leg_pelvis_roll">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_leg_pelvis_pitch">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_leg_knee">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_leg_ankle_pitch">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="left_leg_ankle_roll">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
-    <mu1>1.00000</mu1>
-    <mu2>1.00000</mu2>
+    <selfCollide>false</selfCollide> 
+    <maxContacts>10</maxContacts>
+    <dampingFactor>0.2</dampingFactor>
+    <maxVel>0.0</maxVel>
+    <minDepth>0.0</minDepth>
+    <mu1>100.0</mu1>
+    <mu2>100.0</mu2>
+    <kp>0.0</kp>
+    <kd>0.0</kd>
   </gazebo>
 
   <gazebo reference="right_leg_pelvis_yaw">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="right_leg_pelvis_roll">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="right_leg_pelvis_pitch">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="right_leg_knee">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="right_leg_ankle_pitch">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
+    <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="right_leg_ankle_roll">
     <gravity>true</gravity>
-    <self_collide>false</self_collide>
-    <mu1>1.00000</mu1>
-    <mu2>1.00000</mu2>
+    <selfCollide>false</selfCollide> 
+    <maxContacts>10</maxContacts>
+    <dampingFactor>0.2</dampingFactor>
+    <maxVel>0.0</maxVel>
+    <minDepth>0.0</minDepth>
+    <mu1>100.0</mu1>
+    <mu2>100.0</mu2>
+    <kp>0.0</kp>
+    <kd>0.0</kd>
   </gazebo>
 
   <gazebo reference="j_shoulder_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_high_arm_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_low_arm_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_shoulder_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_high_arm_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_low_arm_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_pelvis_yaw_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_pelvis_roll_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_pelvis_pitch_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_knee_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_ankle_pitch_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_ankle_roll_l">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_pelvis_yaw_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_pelvis_roll_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_pelvis_pitch_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_knee_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_ankle_pitch_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo reference="j_ankle_roll_r">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo>
diff --git a/bioloid_description/urdf/bioloid.xacro b/bioloid_description/urdf/bioloid.xacro
index fab09ee..1b580fe 100755
--- a/bioloid_description/urdf/bioloid.xacro
+++ b/bioloid_description/urdf/bioloid.xacro
@@ -444,7 +444,7 @@
     <child link="right_shoulder"/>
     <origin xyz="-0.07188 0.0 0" rpy="-1.5707 0 0" />
     <axis xyz="-1 0 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -464,7 +464,7 @@
     <child link="right_arm_high"/>
     <origin xyz="0 -0.0145 0.0" rpy="0 0 -1.5707" />
     <axis xyz="0 0 -1" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -484,7 +484,7 @@
     <child link="right_arm_low"/>
     <origin xyz="0.0 -0.0675 0.0" rpy="0 0 0" />
     <axis xyz="0 0 -1" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -504,7 +504,7 @@
     <child link="left_shoulder"/>
     <origin xyz="0.07188 0.0 0" rpy="-1.5707 0 0" />
     <axis xyz="1 0 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -524,7 +524,7 @@
     <child link="left_arm_high"/>
     <origin xyz="0 -0.0145 0.0" rpy="0 0 1.5707" />
     <axis xyz="0 0 -1" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -544,7 +544,7 @@
     <child link="left_arm_low"/>
     <origin xyz="0.0 -0.0675 0.0" rpy="0 0 0" />
     <axis xyz="0 0 -1" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -564,7 +564,7 @@
     <child link="right_leg_pelvis_yaw"/>
     <origin xyz="-0.0385 -0.12037 0.0" rpy="0 -0.7854 0" />
     <axis xyz="0 -1 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -584,7 +584,7 @@
     <child link="right_leg_pelvis_roll"/>
     <origin xyz="0 0 0" rpy="0 0 0" />
     <axis xyz="0 0 1" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -604,7 +604,7 @@
     <child link="right_leg_pelvis_pitch"/>
     <origin xyz="0 0 0" rpy="0 0 0" />
     <axis xyz="1 0 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -624,7 +624,7 @@
     <child link="right_leg_knee"/>
     <origin xyz="0 -0.075 -0.01488" rpy="0 0 0" />
     <axis xyz="-1 0 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -644,7 +644,7 @@
     <child link="right_leg_ankle_pitch"/>
     <origin xyz="0 -0.075 0.01488" rpy="0 0 0" />
     <axis xyz="-1 0 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -664,7 +664,7 @@
     <child link="right_leg_ankle_roll"/>
     <origin xyz="0 0 0" rpy="0 0 0" />
     <axis xyz="0 0 -1" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -684,7 +684,7 @@
     <child link="left_leg_pelvis_yaw"/>
     <origin xyz="0.0385 -0.12037 0.0" rpy="0 0.7853 0" />
     <axis xyz="0 -1 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -704,7 +704,7 @@
     <child link="left_leg_pelvis_roll"/>
     <origin xyz="0 0 0" rpy="0 0 0" />
     <axis xyz="0 0 1" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -724,7 +724,7 @@
     <child link="left_leg_pelvis_pitch"/>
     <origin xyz="0 0 0" rpy="0 0 0" />
     <axis xyz="-1 0 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -744,7 +744,7 @@
     <child link="left_leg_knee"/>
     <origin xyz="0 -0.075 -0.01488" rpy="0 0 0" />
     <axis xyz="1 0 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -764,7 +764,7 @@
     <child link="left_leg_ankle_pitch"/>
     <origin xyz="0 -0.075 0.01488" rpy="0 0 0" />
     <axis xyz="1 0 0" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
@@ -784,7 +784,7 @@
     <child link="left_leg_ankle_roll"/>
     <origin xyz="0 0 0" rpy="0 0 0" />
     <axis xyz="0 0 -1" />
-    <limit effort="1.5" velocity="6.0" lower="-3.14" upper="3.14" />
+    <limit effort="2.5" velocity="12.0" lower="-3.14" upper="3.14" />
     <dynamics damping="0.2"/>
   </joint>
 
diff --git a/bioloid_description/urdf/bioloid_ceabot.gazebo b/bioloid_description/urdf/bioloid_ceabot.gazebo
new file mode 100644
index 0000000..7d6440b
--- /dev/null
+++ b/bioloid_description/urdf/bioloid_ceabot.gazebo
@@ -0,0 +1,49 @@
+<?xml version="1.0"?>
+<robot>
+  <gazebo>
+    <static>0</static>
+  </gazebo>
+
+  <gazebo reference="battery_pack">
+    <material>Gazebo/Grey</material>
+  </gazebo>
+
+  <gazebo reference="controller">
+    <material>Gazebo/Grey</material>
+  </gazebo>
+
+  <gazebo reference="battery_pack">
+    <gravity>true</gravity>
+    <selfCollide>false</selfCollide> 
+    <maxContacts>10</maxContacts>
+    <dampingFactor>0.2</dampingFactor>
+    <maxVel>0.0</maxVel>
+    <minDepth>0.001</minDepth>
+    <mu1>0.200000</mu1>
+    <mu2>0.200000</mu2>
+    <kp>1.0</kp>
+    <kd>0.0</kd>
+  </gazebo>
+
+  <gazebo reference="controller">
+    <gravity>true</gravity>
+    <selfCollide>false</selfCollide> 
+    <maxContacts>10</maxContacts>
+    <dampingFactor>0.2</dampingFactor>
+    <maxVel>0.0</maxVel>
+    <minDepth>0.001</minDepth>
+    <mu1>0.200000</mu1>
+    <mu2>0.200000</mu2>
+    <kp>1.0</kp>
+    <kd>0.0</kd>
+  </gazebo>
+
+  <gazebo reference="j_battery">
+    <implicitSpringDamper>true</implicitSpringDamper>
+  </gazebo>
+
+  <gazebo reference="j_controller">
+    <implicitSpringDamper>true</implicitSpringDamper>
+  </gazebo>
+
+</robot>
diff --git a/bioloid_description/urdf/bioloid_ceabot.xacro b/bioloid_description/urdf/bioloid_ceabot.xacro
index 481ce09..a8a845f 100755
--- a/bioloid_description/urdf/bioloid_ceabot.xacro
+++ b/bioloid_description/urdf/bioloid_ceabot.xacro
@@ -1,6 +1,7 @@
 <robot name="bioloid" xmlns:xacro="http://www.ros.org/wiki/xacro">
  
   <xacro:include filename="$(find bioloid_description)/urdf/bioloid.xacro" />
+  <xacro:include filename="$(find bioloid_description)/urdf/bioloid_ceabot.gazebo" />
   <xacro:include filename="$(find bioloid_description)/urdf/sensors/sharp_ir.xacro" />
   <xacro:include filename="$(find bioloid_description)/urdf/sensors/feet_ir.xacro" />
 
@@ -13,7 +14,7 @@
   <xacro:sharp_ir name="IR3" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8">
     <origin xyz="0 0.05 0.035" rpy="-1.5707 -1.5707 0" />
   </xacro:sharp_ir>
-  <xacro:feet_ir left_parent="left_leg_ankle_roll" right_parent="right_leg_ankle_roll" update_rate="20" range="0.01"/>
+<!--  <xacro:feet_ir left_parent="left_leg_ankle_roll" right_parent="right_leg_ankle_roll" update_rate="20" range="0.01"/>-->
 
   <link name="battery_pack">
     <collision>
diff --git a/bioloid_gazebo/worlds/bioloid.world b/bioloid_gazebo/worlds/bioloid.world
index bd46b04..4c285a6 100644
--- a/bioloid_gazebo/worlds/bioloid.world
+++ b/bioloid_gazebo/worlds/bioloid.world
@@ -2,14 +2,14 @@
 <sdf version="1.4">
   <world name="default">
     <physics type="ode">
-      <real_time_factor>1</real_time_factor>
+      <real_time_factor>1.0</real_time_factor>
       <real_time_update_rate>1000</real_time_update_rate>
       <max_step_size>0.001</max_step_size>
       <gravity>0 0 -9.8</gravity>
       <ode>
         <solver>
           <type>quick</type>
-          <min_step_size>0.001</min_step_size>
+          <min_step_size>0.0001</min_step_size>
           <iters>100</iters>
         </solver>
       </ode>
-- 
GitLab