diff --git a/bioloid_description/meshes/ceabot/obstacle_base.stl b/bioloid_description/meshes/ceabot/obstacle_base.stl
index 5e4201a1fad89723dce5d1b6f264d684199db576..c2594b7bcec639d9cdf5d7f5fee06401a680fab5 100644
Binary files a/bioloid_description/meshes/ceabot/obstacle_base.stl and b/bioloid_description/meshes/ceabot/obstacle_base.stl differ
diff --git a/bioloid_description/meshes/ceabot/obstacle_fence.stl b/bioloid_description/meshes/ceabot/obstacle_fence.stl
new file mode 100644
index 0000000000000000000000000000000000000000..e7c8eca612dc933c91f7c25c3b4950b35466c91e
Binary files /dev/null and b/bioloid_description/meshes/ceabot/obstacle_fence.stl differ
diff --git a/bioloid_description/urdf/ceabot/obstacle_base.xacro b/bioloid_description/urdf/ceabot/obstacle_base.xacro
index ef660a58e516a4fa0a25b38bdd1d094f2d91bba3..64ddf2ed7d7100d5fd4429fee1f7741aab33c2bb 100644
--- a/bioloid_description/urdf/ceabot/obstacle_base.xacro
+++ b/bioloid_description/urdf/ceabot/obstacle_base.xacro
@@ -3,17 +3,11 @@
 <root xmlns:xacro="http://ros.org/wiki/xacro">
 
   <xacro:macro name="obstacle_base" params="name">
-  <!-- IR distance sensors -->
     <link name="${name}_link">
       <inertial>
-        <mass value="50"/>
-        <origin xyz="1.01500000 1.26500000 0.04510729" rpy="0 0 0"/>
-        <inertia ixx="32.72577613" ixy="0.0" ixz="0.0" iyy="22.18978101" iyz="0.0" izz="53.20566219" />
-      </inertial>
-      <inertial>
-        <mass value="1"/>
-        <origin xyz="1.01500000 1.26500000 0.04510729" rpy="0 0 0"/>
-        <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
+        <mass value="40"/>
+        <origin xyz="1.01500000 1.26500000 -0.015" rpy="0 0 0"/>
+        <inertia ixx="21.33933333" ixy="0.0" ixz="0.0" iyy="13.73933333" iyz="0.0" izz="35.07266667" />
       </inertial>
       <visual>
         <origin xyz="0 0 0" rpy="0 0 0"/>
@@ -29,7 +23,49 @@
       </collision>
     </link>
 
+    <link name="${name}_fence_link">
+      <inertial>
+        <mass value="10"/>
+        <origin xyz="1.0100000 1.2600000 0.25" rpy="0 0 0"/>
+        <inertia ixx="10.12791445" ixy="0.0" ixz="0.0" iyy="7.31441888" iyz="0.0" izz="17.02566667" />
+      </inertial>
+      <visual>
+        <origin xyz="0 0 0" rpy="0 0 0"/>
+        <geometry>
+          <mesh filename="package://bioloid_description/meshes/ceabot/obstacle_fence.stl"/>
+        </geometry>
+      </visual>
+      <collision>
+        <origin xyz="0 0 0" rpy="0 0 0"/>
+        <geometry>
+          <mesh filename="package://bioloid_description/meshes/ceabot/obstacle_fence.stl"/>
+        </geometry>
+      </collision>
+    </link>
+
+    <joint name="j_base_fence" type="fixed">
+      <parent link="${name}_link"/>
+      <child link="${name}_fence_link"/>
+      <origin xyz="0.005 0.005 0" rpy="0 0 0" />
+    </joint>
+
     <gazebo reference="${name}_link">
+      <material>Gazebo/Green</material>
+      <gravity>true</gravity>
+      <selfCollide>false</selfCollide>
+      <maxContacts>10</maxContacts>
+      <dampingFactor>0.2</dampingFactor>
+      <maxVel>0.01</maxVel>
+      <minDepth>0.0</minDepth>
+      <fdir1>0 0 0</fdir1>
+      <mu1>1.0</mu1>
+      <mu2>1.0</mu2>
+      <kp>1000000000.0</kp>
+      <kd>1.0</kd>
+    </gazebo>
+
+    <gazebo reference="${name}_fence_link">
+      <material>Gazebo/White</material>
       <gravity>true</gravity>
       <selfCollide>false</selfCollide>
       <maxContacts>10</maxContacts>
diff --git a/bioloid_gazebo/worlds/bioloid.world b/bioloid_gazebo/worlds/bioloid.world
index 1dcf5330be137c2e65162df1617abfa76ac682e8..d92c5cce2485d7c80e0fb5a742dd9f9ce7000039 100644
--- a/bioloid_gazebo/worlds/bioloid.world
+++ b/bioloid_gazebo/worlds/bioloid.world
@@ -2,10 +2,10 @@
 <sdf version="1.4">
   <world name="default">
     <physics type="ode">
-      <real_time_factor>1.0</real_time_factor>
-      <real_time_update_rate>1000</real_time_update_rate>
-<!--      <real_time_factor>0.1</real_time_factor>
-      <real_time_update_rate>100</real_time_update_rate>-->
+<!--      <real_time_factor>1.0</real_time_factor>
+      <real_time_update_rate>1000</real_time_update_rate>-->
+      <real_time_factor>0.1</real_time_factor>
+      <real_time_update_rate>100</real_time_update_rate>
       <max_step_size>0.001</max_step_size>
       <gravity>0 0 -9.8</gravity>
       <ode>