diff --git a/bioloid_apps/launch/action_client_sim.launch b/bioloid_apps/launch/action_client_sim.launch
index 245282df83d5d2f52b345f4d7fb5e0437b59ebd4..da827eaa7361a9c5fe0349277a213a5b4089d2db 100644
--- a/bioloid_apps/launch/action_client_sim.launch
+++ b/bioloid_apps/launch/action_client_sim.launch
@@ -1,6 +1,9 @@
 <launch>
 
+  <arg name="robot" default="bioloid" />
+
   <include file="$(find bioloid_description)/launch/bioloid_sim.launch">
+    <arg name="robot" value="$(arg robot)" />
   </include>
 
   <!-- launch the action client node -->
diff --git a/bioloid_apps/launch/walk_client_sim.launch b/bioloid_apps/launch/walk_client_sim.launch
index 4337448d7b1e8f76ef5b13a542c4ff45b2952c9d..e1f1c926222478070cd2413afa7cfa6c3493f221 100644
--- a/bioloid_apps/launch/walk_client_sim.launch
+++ b/bioloid_apps/launch/walk_client_sim.launch
@@ -1,6 +1,9 @@
 <launch>
 
+  <arg name="robot" default="bioloid" />
+
   <include file="$(find bioloid_description)/launch/bioloid_sim.launch">
+    <arg name="robot" value="$(arg robot)" />
   </include>
 
   <!-- launch the walk client node -->
diff --git a/bioloid_control/launch/bioloid_control.launch b/bioloid_control/launch/bioloid_control.launch
index 1f470dbaa7a4622d6e73d8c3375571f5ceb8d05b..832c1fee02ed2a628975c9120eea00ad159795e4 100644
--- a/bioloid_control/launch/bioloid_control.launch
+++ b/bioloid_control/launch/bioloid_control.launch
@@ -3,8 +3,6 @@
   <!-- Load joint controller configurations from YAML file to parameter server -->
   <rosparam file="$(find bioloid_control)/config/bioloid_control.yaml" command="load"/>
 
-  <param name="motion_file" value="$(find bioloid_controller)/config/bioloid_motions.mtn"/>
-
   <!-- load the controllers -->
   <node name="controller_spawner" 
         pkg="controller_manager" 
diff --git a/bioloid_description/launch/bioloid_base.launch b/bioloid_description/launch/bioloid_base.launch
index 3c3c5ad68b69f753830ce284c2ab16b4f67c8835..a0804862d879115b1dfa4553bebe07744bbf3d89 100644
--- a/bioloid_description/launch/bioloid_base.launch
+++ b/bioloid_description/launch/bioloid_base.launch
@@ -1,13 +1,15 @@
 <launch>
+  <arg name="robot" default="bioloid" />
+
   <!-- Convert an xacro and put on parameter server -->
   <param name="robot_description"
-         command="$(find xacro)/xacro.py '$(find bioloid_description)/urdf/bioloid.xacro'" />
+         command="$(find xacro)/xacro.py '$(find bioloid_description)/urdf/$(arg robot).xacro'" />
 
   <node pkg="robot_state_publisher" type="state_publisher" name="bioloid_tf_broadcaster">
     <param name="tf_prefix" type="string" value="/bioloid"/>
     <param name="publish_frequency" type="double" value="20.0"/>
     <remap from="/joint_states" to="/bioloid/joint_states" />
-  </node>>
+  </node>
 
   <node name="rviz" 
         pkg="rviz" 
diff --git a/bioloid_description/launch/bioloid_sim.launch b/bioloid_description/launch/bioloid_sim.launch
index ad41657e644a312e4272fcd5eb5acc7a8a1421c8..0a3c0ecf713c7ea642e3ef9a62f4c406aa90f472 100644
--- a/bioloid_description/launch/bioloid_sim.launch
+++ b/bioloid_description/launch/bioloid_sim.launch
@@ -1,4 +1,7 @@
 <launch>
+
+  <arg name="robot" default="bioloid" />
+
   <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
   <include file="$(find gazebo_ros)/launch/empty_world.launch">
     <arg name="world_name" value="$(find bioloid_gazebo)/worlds/bioloid.world"/>
@@ -8,7 +11,7 @@
 
   <!-- Convert an xacro and put on parameter server -->
   <param name="robot_description"
-         command="$(find xacro)/xacro.py '$(find bioloid_description)/urdf/bioloid.xacro'" />
+         command="$(find xacro)/xacro.py '$(find bioloid_description)/urdf/$(arg robot).xacro'" />
 
   <node pkg="robot_state_publisher" type="state_publisher" name="bioloid_tf_broadcaster">
     <param name="tf_prefix" type="string" value="/bioloid"/>
diff --git a/bioloid_description/launch/bioloid_test.launch b/bioloid_description/launch/bioloid_test.launch
index 9f18a50428aad9a6d160f829dacfb947beba1d1e..83a8d0d693c0576a097978af1ca37f1a1a4c6750 100644
--- a/bioloid_description/launch/bioloid_test.launch
+++ b/bioloid_description/launch/bioloid_test.launch
@@ -1,7 +1,10 @@
 <launch>
+
+  <arg name="robot" default="bioloid" /> 
+
   <!-- Convert an xacro and put on parameter server -->
   <param name="robot_description"
-         command="$(find xacro)/xacro.py '$(find bioloid_description)/urdf/bioloid.xacro'" />
+         command="$(find xacro)/xacro.py '$(find bioloid_description)/urdf/$(arg robot).xacro'" />
 
   <node pkg="robot_state_publisher" type="state_publisher" name="bioloid_tf_broadcaster">
     <param name="tf_prefix" type="string" value="/bioloid"/>
diff --git a/bioloid_description/meshes/battery_pack2.stl b/bioloid_description/meshes/battery_pack2.stl
new file mode 100644
index 0000000000000000000000000000000000000000..1e62c9d47f507d5252378c4d6f63147303f9182f
Binary files /dev/null and b/bioloid_description/meshes/battery_pack2.stl differ
diff --git a/bioloid_description/urdf/bioloid_low_res.xacro b/bioloid_description/urdf/bioloid_low_res.xacro
new file mode 100755
index 0000000000000000000000000000000000000000..0493a6a558e4cc11c9f9acb88f4302b5dc17b70a
--- /dev/null
+++ b/bioloid_description/urdf/bioloid_low_res.xacro
@@ -0,0 +1,802 @@
+<robot name="bioloid" xmlns:xacro="http://www.ros.org/wiki/xacro">
+ 
+  <xacro:include filename="$(find bioloid_description)/urdf/bioloid.gazebo" />
+
+  <link name="base_link">
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/body_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/body_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.28151649" />
+      <origin xyz="0.0 -0.03753515 0.00033516" rpy="0 0 0"/>
+      <inertia ixx="0.00006808" ixy="0.00000000" ixz="0.00000029" iyy="0.00006762" iyz="-0.00000053" izz="0.00009639" />
+    </inertial>
+  </link>
+
+  <link name="right_shoulder">
+    <collision>
+      <origin xyz="0.0 -0.0145 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_shoulder_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0.0 -0.0145 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_shoulder_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.00795999" />
+      <origin xyz="0.01223141 0.01071920 0.00000000" rpy="0 0 0"/>
+      <inertia ixx="0.00000355" ixy="0.00000031" ixz="0.00000000" iyy="0.00000349" iyz="0.00000000" izz="0.00000147" />
+    </inertial>
+  </link>
+
+  <link name="right_arm_high" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_arm_high_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_arm_high_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.06399809" />
+      <origin xyz="-0.00002662 -0.01859163 0.00083789" rpy="0 0 0"/>
+      <inertia ixx="0.00000410" ixy="0.00000000" ixz="0.00000000" iyy="0.00000353" iyz="0.00000000" izz="0.00000182" />
+    </inertial>
+  </link>
+
+  <link name="right_arm_low" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_arm_low_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0.00 0.0 0.0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_arm_low_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.06340277" />
+      <origin xyz="-0.00032576 -0.01820781 0.00084575" rpy="0 0 0"/>
+      <inertia ixx="0.00000200" ixy="-0.00000033" ixz="0.00000000" iyy="0.00000169" iyz="0.00000000" izz="0.00000157" />
+    </inertial>
+  </link>
+
+  <link name="left_shoulder">
+    <collision>
+      <origin xyz="0.0 -0.0145 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_shoulder_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0.0 -0.0145 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_shoulder_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.00796031" />
+      <origin xyz="-0.01223141 0.01071920 0.00000000" rpy="0 0 0"/>
+      <inertia ixx="0.00000355" ixy="-0.00000031" ixz="0.00000000" iyy="0.00000349" iyz="0.00000000" izz="0.00000147" />
+    </inertial>
+  </link>
+
+  <link name="left_arm_high" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_arm_high_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_arm_high_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.06399809" />
+      <origin xyz="-0.00002662 -0.01859163 0.00083789" rpy="0 0 0"/>
+      <inertia ixx="0.00000410" ixy="-0.000000" ixz="0.00000000" iyy="0.00000353" iyz="0.00000000" izz="0.00000182" />
+    </inertial>
+  </link>
+
+  <link name="left_arm_low" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_arm_low_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0.00 0.0 0.0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_arm_low_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.06340277" />
+      <origin xyz="0.00027383 -0.01820781 0.00084575" rpy="0 0 0"/>
+      <inertia ixx="0.00000200" ixy="-0.00000033" ixz="0.00000000" iyy="0.00000169" iyz="0.00000000" izz="0.00000157" />
+    </inertial>
+  </link>
+
+  <link name="right_leg_pelvis_yaw" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_pelvis_yaw_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0.0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_pelvis_yaw_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.01083078" />
+      <origin xyz="-0.00000246 0.01893788 -0.01648262" rpy="0 0 0"/>
+      <inertia ixx="0.00001023" ixy="0.0" ixz="0.0" iyy="0.00000978" iyz="0.00000008" izz="0.00000205" />
+    </inertial>
+  </link>
+
+  <link name="right_leg_pelvis_roll" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_pelvis_roll_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_pelvis_roll_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.11724768" />
+      <origin xyz="0.00047126 -0.01276672 -0.01614616" rpy="0 0 0"/>
+      <inertia ixx="0.00000754" ixy="0.0" ixz="0.0" iyy="0.00000897" iyz="0.00000047" izz="0.00000303" />
+    </inertial>
+  </link>
+
+  <link name="right_leg_pelvis_pitch" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_pelvis_pitch_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_pelvis_pitch_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.02111586" />
+      <origin xyz="0.00000000 -0.04341218 -0.00107102" rpy="0 0 0"/>
+      <inertia ixx="0.00001158" ixy="0.0" ixz="0.0" iyy="0.00000965" iyz="0.00000090" izz="0.00001750" />
+    </inertial>
+  </link>
+
+  <link name="right_leg_knee" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_knee_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_knee_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.07160661" />
+      <origin xyz="0.00074885 -0.00918420 0.01330283" rpy="0 0 0"/>
+      <inertia ixx="0.00000785" ixy="0.0" ixz="0.0" iyy="0.00000697" iyz="0.00000003" izz="0.00001221" />
+    </inertial>
+  </link>
+
+  <link name="right_leg_ankle_pitch" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_ankle_pitch_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_ankle_pitch_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.11724768" />
+      <origin xyz="0.00044344 0.01276672 -0.01617397" rpy="0 0 0"/>
+      <inertia ixx="0.00000754" ixy="0.0" ixz="0.0" iyy="0.00000897" iyz="-0.00000047" izz="0.00000303" />
+    </inertial>
+  </link>
+
+  <link name="right_leg_ankle_roll" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_ankle_roll_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/right_leg_ankle_roll_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.03089600" />
+      <origin xyz="0.00000000 -0.02582749 -0.00471367" rpy="0 0 0"/>
+      <inertia ixx="0.00003001" ixy="0.0" ixz="0.0" iyy="0.00003576" iyz="-0.00000137" izz="0.00000999" />
+    </inertial>
+  </link>
+
+  <link name="left_leg_pelvis_yaw" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_pelvis_yaw_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0.0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_pelvis_yaw_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.01083078" />
+      <origin xyz="-0.00000246 0.01893788 -0.01648262" rpy="0 0 0"/>
+      <inertia ixx="0.00001023" ixy="0.0" ixz="0.0" iyy="0.00000978" iyz="0.00000008" izz="0.00000205" />
+  </inertial>
+  </link>
+
+  <link name="left_leg_pelvis_roll" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_pelvis_roll_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_pelvis_roll_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.11724768" />
+      <origin xyz="-0.00044344 -0.01276672 -0.01617397" rpy="0 0 0"/>
+      <inertia ixx="0.00000754" ixy="0.0" ixz="0.0" iyy="0.00000897" iyz="0.00000047" izz="0.00000303" />
+    </inertial>
+  </link>
+
+  <link name="left_leg_pelvis_pitch" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_pelvis_pitch_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_pelvis_pitch_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.02111586" />
+      <origin xyz="0.00000000 -0.04341217 -0.00107156" rpy="0 0 0"/>
+      <inertia ixx="0.00001158" ixy="0.0" ixz="0.0" iyy="0.00000965" iyz="0.00000090" izz="0.00001750" />
+    </inertial>
+  </link>
+
+  <link name="left_leg_knee" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_knee_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_knee_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.07160661" />
+      <origin xyz="-0.00074886 -0.00922974 0.01330148" rpy="0 0 0"/>
+      <inertia ixx="0.00000785" ixy="0.0" ixz="0.0" iyy="0.00000697" iyz="0.00000003" izz="0.00001221" />
+    </inertial>
+  </link>
+
+  <link name="left_leg_ankle_pitch" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_ankle_pitch_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_ankle_pitch_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.11724768" />
+      <origin xyz="-0.00047126 0.01276672 -0.01614616" rpy="0 0 0"/>
+      <inertia ixx="0.00000754" ixy="0.0" ixz="0.0" iyy="0.00000897" iyz="-0.00000047" izz="0.00000303" />
+    </inertial>
+  </link>
+
+  <link name="left_leg_ankle_roll" >
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_ankle_roll_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/left_leg_ankle_roll.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.03089600" />
+      <origin xyz="0.00000000 -0.02582749 -0.00471367" rpy="0 0 0"/>
+      <inertia ixx="0.00003001" ixy="0.0" ixz="0.0" iyy="0.00003576" iyz="-0.00000137" izz="0.00000999" />
+    </inertial>
+  </link>
+
+  <joint name="j_shoulder_r" type="revolute">
+    <parent link="base_link"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_shoulder_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_shoulder_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="shoulder_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_high_arm_r" type="revolute">
+    <parent link="right_shoulder"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_high_arm_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_high_arm_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="high_arm_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_low_arm_r" type="revolute">
+    <parent link="right_arm_high"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_low_arm_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_low_arm_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="low_arm_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_shoulder_l" type="revolute">
+    <parent link="base_link"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_shoulder_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_shoulder_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="shoulder_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_high_arm_l" type="revolute">
+    <parent link="left_shoulder"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_high_arm_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_high_arm_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="high_arm_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_low_arm_l" type="revolute">
+    <parent link="left_arm_high"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_low_arm_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_low_arm_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="low_arm_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_pelvis_yaw_r" type="revolute">
+    <parent link="base_link"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_pelvis_yaw_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_pelvis_yaw_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="pelvis_yaw_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_pelvis_roll_r" type="revolute">
+    <parent link="right_leg_pelvis_yaw"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_pelvis_roll_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_pelvis_roll_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="pelvis_roll_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_pelvis_pitch_r" type="revolute">
+    <parent link="right_leg_pelvis_roll"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_pelvis_pitch_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_pelvis_pitch_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="pelvis_pitch_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_knee_r" type="revolute">
+    <parent link="right_leg_pelvis_pitch"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_knee_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_knee_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="knee_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_ankle_pitch_r" type="revolute">
+    <parent link="right_leg_knee"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_ankle_pitch_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_ankle_pitch_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="ankle_pitch_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_ankle_roll_r" type="revolute">
+    <parent link="right_leg_ankle_pitch"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_ankle_roll_r">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_ankle_roll_r">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="ankle_roll_r_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_pelvis_yaw_l" type="revolute">
+    <parent link="base_link"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_pelvis_yaw_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_pelvis_yaw_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="pelvis_yaw_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_pelvis_roll_l" type="revolute">
+    <parent link="left_leg_pelvis_yaw"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_pelvis_roll_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_pelvis_roll_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="pelvis_roll_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_pelvis_pitch_l" type="revolute">
+    <parent link="left_leg_pelvis_roll"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_pelvis_pitch_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_pelvis_pitch_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="pelvis_pitch_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_knee_l" type="revolute">
+    <parent link="left_leg_pelvis_pitch"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_knee_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_knee_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="knee_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_ankle_pitch_l" type="revolute">
+    <parent link="left_leg_knee"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_ankle_pitch_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_ankle_pitch_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="ankle_pitch_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+  <joint name="j_ankle_roll_l" type="revolute">
+    <parent link="left_leg_ankle_pitch"/>
+    <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" />
+    <dynamics damping="0.2"/>
+  </joint>
+
+  <transmission name="tran_ankle_roll_l">
+    <type>transmission_interface/SimpleTransmission</type>
+    <joint name="j_ankle_roll_l">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+    </joint>
+    <actuator name="ankle_roll_l_motor">
+      <hardwareInterface>EffortJointInterface</hardwareInterface>
+      <mechanicalReduction>1</mechanicalReduction>
+    </actuator>
+  </transmission>
+
+</robot>
diff --git a/bioloid_description/urdf/tina.gazebo b/bioloid_description/urdf/tina.gazebo
new file mode 100644
index 0000000000000000000000000000000000000000..f501cf9249561838e7ebc5edba42a72a7c2671f8
--- /dev/null
+++ b/bioloid_description/urdf/tina.gazebo
@@ -0,0 +1,40 @@
+<?xml version="1.0"?>
+<robot>
+  <gazebo>
+    <static>0</static>
+  </gazebo>
+
+  <gazebo reference="battery_pack">
+    <material>Gazebo/Grey</material>
+  </gazebo>
+
+  <gazebo reference="battery_pack">
+    <gravity>true</gravity>
+    <self_collide>false</self_collide>
+    <mu1>0.200000</mu1>
+    <mu2>0.200000</mu2>
+  </gazebo>
+
+  <gazebo reference="controller">
+    <material>Gazebo/Grey</material>
+  </gazebo>
+
+  <gazebo reference="controller">
+    <gravity>true</gravity>
+    <self_collide>false</self_collide>
+    <mu1>0.200000</mu1>
+    <mu2>0.200000</mu2>
+  </gazebo>
+
+  <gazebo reference="battery_charger">
+    <material>Gazebo/Grey</material>
+  </gazebo>
+
+  <gazebo reference="battery_charger">
+    <gravity>true</gravity>
+    <self_collide>false</self_collide>
+    <mu1>0.200000</mu1>
+    <mu2>0.200000</mu2>
+  </gazebo>
+
+</robot>
diff --git a/bioloid_description/urdf/tina.xacro b/bioloid_description/urdf/tina.xacro
new file mode 100755
index 0000000000000000000000000000000000000000..99f7f8f34bce62abe4d1dd7fa0622a3f9fe4bbc9
--- /dev/null
+++ b/bioloid_description/urdf/tina.xacro
@@ -0,0 +1,93 @@
+<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/tina.gazebo" />
+
+  <link name="battery_pack">
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/battery_pack2_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/battery_pack2.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.12" />
+      <origin xyz="0.00051 -0.014743307 0.0092685038" rpy="0 0 0"/>
+      <inertia ixx="0.00009383" ixy="-0.000001001" ixz="0.000001666" iyy="0.000087547" iyz="-0.00001616" izz="0.000153" />
+    </inertial>
+  </link>
+
+  <joint name="j_battery" type="fixed">
+    <parent link="base_link"/>
+    <child link="battery_pack"/>
+    <origin xyz="0 0 0.023" rpy="0 0 0" />
+  </joint>
+
+  <link name="controller">
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/controller_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/controller_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+      <mass value="0.084" />
+      <origin xyz="0.00307783 -0.01310032 -0.00554360" rpy="0 0 0"/>
+      <inertia ixx="0.00005038" ixy="-0.00000275" ixz="-0.00000190" iyy="0.00006332" iyz="0.00000602" izz="0.00010308" />
+    </inertial>
+  </link>
+
+  <joint name="j_controller" type="fixed">
+    <parent link="base_link"/>
+    <child link="controller"/>
+    <origin xyz="0 0 -0.0276" rpy="0 0 0" />
+  </joint>
+
+  <link name="battery_charger">
+    <collision>
+      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/smart_battery_charger_board_bb.stl" />
+      </geometry>
+    </collision>
+    <visual>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://bioloid_description/meshes/bounding_boxes/smart_battery_charger_board_bb.stl" />
+      </geometry>
+      <material name="Grey">
+        <color rgba="0.79 0.82 0.93 1.0"/>
+      </material>
+    </visual>
+    <inertial>
+     <mass value="0.029" />
+      <origin xyz="0.0 0.0 -0.0048980564" rpy="0 0 0"/>
+      <inertia ixx="0.000003347" ixy="0.0" ixz="0.0" iyy="0.000018552" iyz="0.0" izz="0.000019243" />
+    </inertial>
+  </link>
+
+  <joint name="j_battery_charger" type="fixed">
+    <parent link="base_link"/>
+    <child link="battery_charger"/>
+    <origin xyz="0 -0.0672 -0.0222" rpy="0 0 0" />
+  </joint>
+
+</robot>
diff --git a/bioloid_gazebo/launch/bioloid_gazebo.launch b/bioloid_gazebo/launch/bioloid_gazebo.launch
index fa0322ceb03464e2a8559986c7f4f9f4cf869bd0..a0bfce7ef5e8c742e54d0582ce99d024349517c9 100644
--- a/bioloid_gazebo/launch/bioloid_gazebo.launch
+++ b/bioloid_gazebo/launch/bioloid_gazebo.launch
@@ -1,5 +1,7 @@
 <launch>
 
+  <arg name="robot" default="bioloid" />
+
   <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
   <include file="$(find gazebo_ros)/launch/empty_world.launch">
     <arg name="world_name" value="$(find bioloid_gazebo)/worlds/bioloid.world"/>
@@ -7,7 +9,9 @@
     <!-- more default parameters can be changed here -->
   </include>
 
-  <include file="$(find bioloid_description)/launch/bioloid_base.launch"/>
+  <include file="$(find bioloid_description)/launch/bioloid_base.launch">
+    <arg name="robot" value="$(arg robot)" />
+  </include>
 
   <!-- Spawn a robot into Gazebo -->
   <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model bioloid -x 0 -y 0 -z 0.32 -R 1.5707 -P 0 -Y 0"/>