diff --git a/config/description.rviz b/config/description.rviz
index 9371f425807fa6c39dce39254f1686baa0169a51..11adc8f84f8984e0c4bdca1d120a49a9c359268e 100644
--- a/config/description.rviz
+++ b/config/description.rviz
@@ -5,8 +5,11 @@ Panels:
     Property Tree Widget:
       Expanded:
         - /Global Options1
+        - /Status1
+        - /Grid1
+        - /Models1
         - /Models1/RobotModel1
-      Splitter Ratio: 0.69186
+      Splitter Ratio: 0.69186002
     Tree Height: 421
   - Class: rviz/Selection
     Name: Selection
@@ -16,7 +19,7 @@ Panels:
       - /2D Nav Goal1
       - /Publish Point1
     Name: Tool Properties
-    Splitter Ratio: 0.588679
+    Splitter Ratio: 0.588679016
   - Class: rviz/Views
     Expanded:
       - /Current View1
@@ -27,6 +30,8 @@ Panels:
     Name: Time
     SyncMode: 0
     SyncSource: ""
+Toolbars:
+  toolButtonStyle: 2
 Visualization Manager:
   Class: ""
   Displays:
@@ -36,7 +41,7 @@ Visualization Manager:
       Color: 160; 160; 164
       Enabled: true
       Line Style:
-        Line Width: 0.03
+        Line Width: 0.0299999993
         Value: Lines
       Name: Grid
       Normal Cell Count: 0
@@ -49,93 +54,22 @@ Visualization Manager:
       Reference Frame: <Fixed Frame>
       Value: true
     - Class: rviz/TF
-      Enabled: true
+      Enabled: false
       Frame Timeout: 15
       Frames:
         All Enabled: true
-        base_link:
-          Value: true
-        camera:
-          Value: true
-        camera_board:
-          Value: true
-        camera_depth_frame:
-          Value: true
-        camera_depth_optical_frame:
-          Value: true
-        camera_link:
-          Value: true
-        camera_link2:
-          Value: true
-        camera_optical:
-          Value: true
-        camera_rgb_frame:
-          Value: true
-        camera_rgb_optical_frame:
-          Value: true
-        camera_rgb_optical_frame2:
-          Value: true
-        front_left_axel_link:
-          Value: true
-        front_left_wheel_link:
-          Value: true
-        front_right_axel_link:
-          Value: true
-        front_right_wheel_link:
-          Value: true
-        imu:
-          Value: true
-        laser:
-          Value: true
-        rear_left_wheel_link:
-          Value: true
-        rear_right_wheel_link:
-          Value: true
-        sensor_board:
-          Value: true
-      Marker Scale: 0.2
+      Marker Scale: 0.200000003
       Name: TF
       Show Arrows: false
       Show Axes: true
       Show Names: true
       Tree:
-        base_link:
-          front_left_axel_link:
-            front_left_wheel_link:
-              {}
-          front_right_axel_link:
-            front_right_wheel_link:
-              {}
-          rear_left_wheel_link:
-            {}
-          rear_right_wheel_link:
-            {}
-          sensor_board:
-            camera_board:
-              camera:
-                camera_optical:
-                  {}
-              camera_link:
-                camera_depth_frame:
-                  {}
-                camera_depth_optical_frame:
-                  {}
-                camera_rgb_frame:
-                  {}
-                camera_rgb_optical_frame:
-                  {}
-              camera_link2:
-                camera_rgb_optical_frame2:
-                  {}
-            imu:
-              {}
-            laser:
-              {}
+        {}
       Update Interval: 0
-      Value: true
+      Value: false
     - Class: rviz/Group
       Displays:
-        - Alpha: 0.9
+        - Alpha: 1
           Class: rviz/RobotModel
           Collision Enabled: false
           Enabled: true
@@ -149,93 +83,57 @@ Visualization Manager:
               Alpha: 1
               Show Axes: false
               Show Trail: false
-              Value: true
-            camera:
+            body:
               Alpha: 1
               Show Axes: false
               Show Trail: false
               Value: true
-            camera_board:
+            front_left_wheel:
               Alpha: 1
               Show Axes: false
               Show Trail: false
               Value: true
-            camera_depth_frame:
-              Alpha: 1
-              Show Axes: false
-              Show Trail: false
-            camera_depth_optical_frame:
-              Alpha: 1
-              Show Axes: false
-              Show Trail: false
-            camera_link:
+            front_lidar_rplidar_base:
               Alpha: 1
               Show Axes: false
               Show Trail: false
               Value: true
-            camera_link2:
-              Alpha: 1
-              Show Axes: false
-              Show Trail: false
-            camera_optical:
-              Alpha: 1
-              Show Axes: false
-              Show Trail: false
-            camera_rgb_frame:
-              Alpha: 1
-              Show Axes: false
-              Show Trail: false
-            camera_rgb_optical_frame:
+            front_lidar_rplidar_scan_frame:
               Alpha: 1
               Show Axes: false
               Show Trail: false
-            camera_rgb_optical_frame2:
-              Alpha: 1
-              Show Axes: false
-              Show Trail: false
-            front_left_axel_link:
-              Alpha: 1
-              Show Axes: false
-              Show Trail: false
-            front_left_wheel_link:
+            front_right_wheel:
               Alpha: 1
               Show Axes: false
               Show Trail: false
               Value: true
-            front_right_axel_link:
-              Alpha: 1
-              Show Axes: false
-              Show Trail: false
-            front_right_wheel_link:
+            rear_left_wheel:
               Alpha: 1
               Show Axes: false
               Show Trail: false
               Value: true
-            imu:
+            rear_right_wheel:
               Alpha: 1
               Show Axes: false
               Show Trail: false
               Value: true
-            laser:
+            side_left_base:
               Alpha: 1
               Show Axes: false
               Show Trail: false
               Value: true
-            rear_left_wheel_link:
+            side_left_ranger1d:
               Alpha: 1
               Show Axes: false
               Show Trail: false
-              Value: true
-            rear_right_wheel_link:
+            steer_left:
               Alpha: 1
               Show Axes: false
               Show Trail: false
-              Value: true
-            sensor_board:
+            steer_right:
               Alpha: 1
               Show Axes: false
               Show Trail: false
-              Value: true
           Name: RobotModel
           Robot Description: robot_description
           TF Prefix: ""
@@ -247,6 +145,7 @@ Visualization Manager:
   Enabled: true
   Global Options:
     Background Color: 48; 48; 48
+    Default Light: true
     Fixed Frame: base_link
     Frame Rate: 30
   Name: root
@@ -268,22 +167,25 @@ Visualization Manager:
   Views:
     Current:
       Class: rviz/Orbit
-      Distance: 0.71098
+      Distance: 0.476244211
       Enable Stereo Rendering:
-        Stereo Eye Separation: 0.06
+        Stereo Eye Separation: 0.0599999987
         Stereo Focal Distance: 1
         Swap Stereo Eyes: false
         Value: false
       Focal Point:
-        X: 0.122431
-        Y: -0.0544084
-        Z: 0.0200973
+        X: 0.222137496
+        Y: 0.128144473
+        Z: 0.00814992562
+      Focal Shape Fixed Size: true
+      Focal Shape Size: 0.0500000007
+      Invert Z Axis: false
       Name: Current View
-      Near Clip Distance: 0.01
-      Pitch: 0.485399
+      Near Clip Distance: 0.00999999978
+      Pitch: 0.310399383
       Target Frame: base_link
       Value: Orbit (rviz)
-      Yaw: 1.1054
+      Yaw: 1.22540057
     Saved: ~
 Window Geometry:
   Displays:
@@ -291,7 +193,7 @@ Window Geometry:
   Height: 636
   Hide Left Dock: false
   Hide Right Dock: false
-  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000236fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000236000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002520000014e0000000000000000000000010000014f00000236fc0200000006fb0000001600530052003300300030005f0069006d0061006700650000000028000000b40000000000000000fb00000014006700700073005f00630061006d0065007200610000000028000001170000000000000000fb00000024004c0069006e00650044006500740065006300740069006f006e0049006d0061006700650000000028000002360000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000001d70000020d000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000064f0000003efc0100000002fb0000000800540069006d006500000000000000064f000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000003880000023600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000236fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000236000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002520000014e0000000000000000000000010000014f00000236fc0200000006fb0000001600530052003300300030005f0069006d0061006700650000000028000000b40000000000000000fb00000014006700700073005f00630061006d0065007200610000000028000001170000000000000000fb00000024004c0069006e00650044006500740065006300740069006f006e0049006d0061006700650000000028000002360000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000001d70000020d000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000064f0000003efc0100000002fb0000000800540069006d006500000000000000064f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003880000023600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
diff --git a/launch/description.launch b/launch/description.launch
index 74cbf21de0172ba1136c37c39b8a991f541cccd2..4d044b11309227b5d158f572bf10fd680559534e 100644
--- a/launch/description.launch
+++ b/launch/description.launch
@@ -2,10 +2,9 @@
 <launch>
 
   <arg name="name" default="model_car"/>
-  <arg name="model" default="car"/>
   
   <param name="robot_description"
-         command="$(find xacro)/xacro --inorder '$(find model_car_description)/urdf/$(arg model).xacro'" />
+         command="$(find xacro)/xacro --inorder '$(find model_car_description)/urdf/car.xacro'" />
 
   <node pkg="robot_state_publisher" type="robot_state_publisher" name="tf_broadcaster_$(arg name)">
     <param name="publish_frequency" type="double" value="50.0"/>
diff --git a/launch/description_test.launch b/launch/description_test.launch
index 7c45ed0197ce2b69758f875b39bb1f6c91c9a0f5..e755d3096a703172edf8edcdb767a6277b6ffec2 100644
--- a/launch/description_test.launch
+++ b/launch/description_test.launch
@@ -2,17 +2,14 @@
 <launch>
   
   <arg name="name"  default="model_car"/>
-  <arg name="model" default="car"/>
 
   <include file="$(find model_car_description)/launch/description.launch">
     <arg name="name"  value="$(arg name)"/>
-    <arg name="model" value="$(arg model)"/>
   </include>
   
   <node name="joint_state_publisher"
-        pkg ="joint_state_publisher"
-        type="joint_state_publisher">
-    <param name="use_gui" value="true"/>
+        pkg ="joint_state_publisher_gui"
+        type="joint_state_publisher_gui">
     <remap from="/joint_states" 
              to="/$(arg name)/joint_states" />
   </node>
diff --git a/meshes/IMU.stl b/meshes/IMU.stl
deleted file mode 100644
index bb959d9eb2c20480a437b60dff5a53b8f855e1d5..0000000000000000000000000000000000000000
Binary files a/meshes/IMU.stl and /dev/null differ
diff --git a/meshes/RP-LIDAR.stl b/meshes/RP-LIDAR.stl
deleted file mode 100644
index 66bee050a69b5c8c149c9f736d691bd9051e399e..0000000000000000000000000000000000000000
Binary files a/meshes/RP-LIDAR.stl and /dev/null differ
diff --git a/meshes/base.stl b/meshes/base.stl
new file mode 100644
index 0000000000000000000000000000000000000000..722564bf5a5c2b266af230eddba850a5bbe69595
Binary files /dev/null and b/meshes/base.stl differ
diff --git a/meshes/camera_board.stl b/meshes/camera_board.stl
deleted file mode 100644
index 58c0a7c2e648f3074e4a1810b7115ff1ba56b85f..0000000000000000000000000000000000000000
Binary files a/meshes/camera_board.stl and /dev/null differ
diff --git a/meshes/chassis.stl b/meshes/chassis.stl
deleted file mode 100644
index f2700e8e2d7b232d73ed298bc717491038f78815..0000000000000000000000000000000000000000
Binary files a/meshes/chassis.stl and /dev/null differ
diff --git a/meshes/creative_camera.stl b/meshes/creative_camera.stl
deleted file mode 100644
index 9909895bb52a4594c7e3df64abe6f3568e7acac7..0000000000000000000000000000000000000000
Binary files a/meshes/creative_camera.stl and /dev/null differ
diff --git a/meshes/gps_camera.stl b/meshes/gps_camera.stl
deleted file mode 100644
index 4136b65973f613fe24ff1a7b8be354f7273b8ea5..0000000000000000000000000000000000000000
Binary files a/meshes/gps_camera.stl and /dev/null differ
diff --git a/meshes/sensor_board.stl b/meshes/sensor_board.stl
deleted file mode 100644
index cdfcf295e5fb1211a36f60523d4d69778acba045..0000000000000000000000000000000000000000
Binary files a/meshes/sensor_board.stl and /dev/null differ
diff --git a/meshes/wheel.stl b/meshes/wheel.stl
index d3230315a4c3cead2391126624171777cccbb6a1..7fc3e0ce2e0236815fb4175b5854696b7a7d092a 100644
Binary files a/meshes/wheel.stl and b/meshes/wheel.stl differ
diff --git a/urdf/car.xacro b/urdf/car.xacro
index 007105be9c810c9572a9a8115b2b6722ec9277b0..23d1137dcbe6f78694ac1dc1ce9ac7cd9c086328 100644
--- a/urdf/car.xacro
+++ b/urdf/car.xacro
@@ -1,21 +1,9 @@
 <?xml version="1.0"?>
 
-<robot name="model_car" xmlns:xacro="http://www.ros.org/wiki/xacro">
+<robot name="model_car" xmlns:xacro="http://ros.org/wiki/xacro">
 
   <!-- Included URDF Files -->
-  <xacro:include filename="$(find model_car_description)/urdf/include/materials.xacro" />
-  
   <xacro:include filename="$(find model_car_description)/urdf/include/platform.xacro" />
-  <xacro:include filename="$(find model_car_description)/urdf/include/platform.gazebo" />
-
   <xacro:include filename="$(find model_car_description)/urdf/include/sensors.xacro" />
-  <xacro:include filename="$(find model_car_description)/urdf/include/sensors.gazebo" />
-  
-  <!-- gazebo sensors -->
-  <xacro:include filename="$(find model_car_description)/urdf/include/sensors/imu.gazebo" />
-  <xacro:include filename="$(find model_car_description)/urdf/include/sensors/laser.gazebo" />
-  <xacro:include filename="$(find model_car_description)/urdf/include/sensors/front_rgbd_camera.gazebo" />
-  <!--<xacro:include filename="$(find model_car_description)/urdf/include/sensors/front_rgb_camera.gazebo" />--> <!-- only rgb, no depth-->
-  <xacro:include filename="$(find model_car_description)/urdf/include/sensors/top_camera.gazebo" />
 
 </robot>
diff --git a/urdf/include/materials.xacro b/urdf/include/materials.xacro
deleted file mode 100644
index f4ea8ce144bcd06d6201a30e283f8ff0fe5b1ac8..0000000000000000000000000000000000000000
--- a/urdf/include/materials.xacro
+++ /dev/null
@@ -1,32 +0,0 @@
-<?xml version="1.0"?>
-<robot>
-
-    <material name="Black">
-        <color rgba="0.0 0.0 0.0 1.0"/>
-    </material>
-
-    <material name="Blue">
-        <color rgba="0.0 0.0 0.8 1.0"/>
-    </material>
-
-    <material name="Green">
-        <color rgba="0.0 0.8 0.0 1.0"/>
-    </material>
-
-    <material name="Grey">
-        <color rgba="0.7 0.7 0.7 1.0"/>
-    </material>
-
-    <material name="Grey2">
-        <color rgba="0.9 0.9 0.9 1.0"/>
-    </material>
-
-    <material name="Red">
-        <color rgba="0.8 0.0 0.0 1.0"/>
-    </material>
-
-    <material name="White">
-        <color rgba="1.0 1.0 1.0 1.0"/>
-    </material>
-
-</robot>
\ No newline at end of file
diff --git a/urdf/include/platform.gazebo b/urdf/include/platform.gazebo
index d8ff1a8b913cdee8c47077b18a45697edc3bb1aa..bb3f7666a0ecf4cad635184cbd4b8bad4a85d187 100644
--- a/urdf/include/platform.gazebo
+++ b/urdf/include/platform.gazebo
@@ -4,48 +4,35 @@
     <static>0</static>
   </gazebo>
 
-  <gazebo reference="base_link">
+  <gazebo reference="body">
     <material>Gazebo/Grey</material>
+    <gravity>true</gravity>
+    <self_collide>false</self_collide>
+    <dampingFactor>0.0002</dampingFactor>
+    <mu1>0.300000</mu1>
+    <mu2>1.000000</mu2>
+<!--    <kp>50000000.0</kp>-->
+<!--    <kd>1.0</kd>-->
   </gazebo>
 
-  <gazebo reference="front_left_wheel_link">
+  <gazebo reference="steer_left">
     <material>Gazebo/Black</material>
   </gazebo>
 
-  <gazebo reference="front_right_wheel_link">
+  <gazebo reference="steer_right">
     <material>Gazebo/Black</material>
   </gazebo>
 
-  <gazebo reference="rear_left_wheel_link">
-    <material>Gazebo/Black</material>
-  </gazebo>
-
-  <gazebo reference="rear_right_wheel_link">
-    <material>Gazebo/Black</material>
-  </gazebo>
-
-  <gazebo reference="front_left_axel_front_left_wheel_joint">
-    <implicitSpringDamper>true</implicitSpringDamper>
-  </gazebo>
-
-  <gazebo reference="front_right_axel_front_right_wheel_joint">
-    <implicitSpringDamper>true</implicitSpringDamper>
-  </gazebo>
-
-  <gazebo reference="base_link_rear_left_wheel_joint">
-    <implicitSpringDamper>true</implicitSpringDamper>
-  </gazebo>
-
-  <gazebo reference="base_link_rear_right_wheel_joint">
-    <implicitSpringDamper>true</implicitSpringDamper>
-  </gazebo>
-
-  <gazebo reference="base_link_front_left_axel_joint">
+  <gazebo reference="base_link_2_steer_left_joint">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
-  <gazebo reference="base_link_front_right_axel_joint">
+  <gazebo reference="base_link_2_steer_right_joint">
     <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
   </gazebo>
 
   <gazebo>
diff --git a/urdf/include/platform.xacro b/urdf/include/platform.xacro
index 9af9391190b7c24d2877aa88d3f833fde2096249..cbcf0ff13fdae865bdbc8da6c4e0084e79134bb6 100644
--- a/urdf/include/platform.xacro
+++ b/urdf/include/platform.xacro
@@ -1,33 +1,34 @@
 <?xml version="1.0"?>
 
-<robot name="model_car" xmlns:xacro="http://www.ros.org/wiki/xacro">
+<robot name="model_car" xmlns:xacro="http://ros.org/wiki/xacro">
+
+  <xacro:include filename="$(find model_car_description)/urdf/include/wheel.xacro" />
 
   <xacro:property name="PI" value="3.1415926535897931" />
   <xacro:property name="angle_limit" value="${PI/3.0}" />
-  <xacro:property name="wheel_width" value="0.001" />
 
   <link name="base_link">
   </link>
   
   <link name="body">
     <inertial>
-      <mass value="6" />
-      <origin xyz="0.15971917 0.00000000 0.00197764" />
-      <inertia ixx="0.0067970" ixy="0.0" ixz="-0.0008808"
-               iyy="0.0784672" iyz="0.0" 
-               izz="0.0838770" />
+      <mass value="5.66119736" />
+      <origin xyz="0.18422506 0.00000000 0.0504506" />
+      <inertia ixx="0.02201830" ixy="0.00000000" ixz="-0.00092111"
+               iyy="0.06244486" iyz="0.00000000" 
+               izz="0.06627095" />
     </inertial>
     <visual>
       <origin xyz="0 0 0" rpy="0 0 0" />
       <geometry>
-        <mesh filename="package://model_car_description/meshes/chassis.stl"/>
+        <mesh filename="package://model_car_description/meshes/base.stl"/>
       </geometry>
       <material name="Grey" />
     </visual>
     <collision>
       <origin xyz="0 0 0" rpy="0 0 0" />
       <geometry>
-        <mesh filename="package://model_car_description/meshes/chassis.stl"/>
+        <mesh filename="package://model_car_description/meshes/base.stl"/>
       </geometry>
     </collision>
   </link>
@@ -38,238 +39,73 @@
     <child link="body" />
   </joint>
 
-  <joint name="base_link_rear_left_wheel_joint" type="revolute">
-    <origin xyz="0.0 -0.0825 0" rpy="${PI/2.0} 0 0" />
-    <axis xyz="0 0 1" />
-    <anchor xyz="0 0 0" />
-    <parent link="base_link" />
-    <child link="rear_left_wheel_link" />
-    <limit lower="-1000000000000.0" upper="1000000000000.0" effort="3.0" velocity="124"/>
-  </joint>
+  <!-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ WHEELS ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -->
+  <!-- ======= REAR LEFT ======= -->
+  <xacro:wheel name="rear_left" parent="base_link" direction="1.0">
+    <origin xyz="0 0.108 0" rpy="1.5707 0 3.14159" />
+  </xacro:wheel>
 
-  <transmission name="tran_rear_left">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="base_link_rear_left_wheel_joint">
-      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="rear_left_motor">
-      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
+  <!-- ======= REAR RIGHT ======= -->
+  <xacro:wheel name="rear_right" parent="base_link" direction="-1.0">
+    <origin xyz="0 -0.108 0" rpy="1.5707 0 0" />
+  </xacro:wheel>
 
-  <link name="rear_left_wheel_link">
-    <inertial>
-      <mass value="1" />
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <inertia  ixx="0.0002946" ixy="0.0" ixz="0.0"
-                iyy="0.0002946" iyz="0.0"
-                izz="0.000494" />
-    </inertial>
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/wheel.stl"/>
-      </geometry>
-      <material name="Black" />
-    </visual>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <cylinder radius="0.0315" length="${wheel_width}"/>
-      </geometry>
-    </collision>
+  <link name="steer_left">
   </link>
 
-  <joint name="base_link_rear_right_wheel_joint" type="revolute">
-    <origin xyz="0.0 0.0825 0" rpy="-${PI/2.0} 0 0" />
+  <joint name="base_link_2_steer_left_joint" type="revolute">
+    <origin xyz="0.3666 0.108 0" rpy="0 0 0" />
     <axis xyz="0 0 1" />
     <anchor xyz="0 0 0" />
     <parent link="base_link" />
-    <child link="rear_right_wheel_link" />
-    <limit lower="-1000000000000.0" upper="1000000000000.0" effort="3.0" velocity="124"/>
-  </joint>
-
-  <transmission name="tran_rear_right">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="base_link_rear_right_wheel_joint">
-      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="rear_right_motor">
-      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <link name="rear_right_wheel_link">
-    <inertial>
-      <mass value="1" />
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <inertia  ixx="0.0002946" ixy="0.0" ixz="0.0"
-                iyy="0.0002946" iyz="0.0"
-                izz="0.0004940" />
-    </inertial>
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/wheel.stl"/>
-      </geometry>
-      <material name="Black" />
-    </visual>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <cylinder radius="0.0315" length="${wheel_width}"/>
-      </geometry>
-    </collision>
-  </link>
-
-  <joint name="base_link_front_left_axel_joint" type="revolute">
-    <origin xyz="0.260 -0.0825 0" rpy="${PI/2.0} 0 0" />
-    <axis xyz="0 1 0" />
-    <anchor xyz="0 0 0" />
-    <parent link="base_link" />
-    <child link="front_left_axel_link" />
+    <child link="steer_left" />
     <limit lower="-${angle_limit}" upper="${angle_limit}" effort="9.6" velocity="5.3"/>
     <dynamics damping="0.2"/>
   </joint>
 
-  <transmission name="tran_front_left_axel">
+  <transmission name="tran_steer_left">
     <type>transmission_interface/SimpleTransmission</type>
-    <joint name="base_link_front_left_axel_joint">
+    <joint name="base_link_2_steer_left_joint">
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
     </joint>
-    <actuator name="front_left_axel_motor">
+    <actuator name="steer_left_motor">
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
       <mechanicalReduction>1</mechanicalReduction>
     </actuator>
   </transmission>
 
-  <link name="front_left_axel_link">
-    <inertial>
-      <mass value="0.001" />
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <inertia  ixx="0.00001" ixy="0.0" ixz="0.0"
-                iyy="0.00001" iyz="0.0"
-                izz="0.00001" />
-    </inertial>
-  </link>
-
-  <joint name="front_left_axel_front_left_wheel_joint" type="revolute">
-    <origin xyz="0.0 0.0 0" rpy="0 0 0" />
-    <axis xyz="0 0 1" />
-    <anchor xyz="0 0 0" />
-    <parent link="front_left_axel_link" />
-    <child link="front_left_wheel_link" />
-    <limit lower="-1000000000000.0" upper="1000000000000.0" effort="3.0" velocity="124"/>
-  </joint>
-
-  <transmission name="tran_front_left_wheel">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="front_left_axel_front_left_wheel_joint">
-      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="front_left_wheel_motor">
-      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
+  <!-- ======= FRONT LEFT ======= -->
+  <xacro:wheel name="front_left" parent="steer_left" direction="1.0">
+    <origin xyz="0.0 0.0 0" rpy="1.5707 0 3.14159" />
+  </xacro:wheel>
 
-  <link name="front_left_wheel_link">
-    <inertial>
-      <mass value="1" />
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <inertia  ixx="0.0002946" ixy="0.0" ixz="0.0"
-                iyy="0.0002946" iyz="0.0"
-                izz="0.0004940" />
-    </inertial>
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/wheel.stl"/>
-      </geometry>
-      <material name="Black" />
-    </visual>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <cylinder radius="0.0315" length="${wheel_width}"/>
-      </geometry>
-    </collision>
+  <link name="steer_right">
   </link>
 
-  <joint name="base_link_front_right_axel_joint" type="revolute">
-    <origin xyz="0.260 0.0825 0" rpy="-${PI/2.0} 0 0" />
-    <axis xyz="0 1 0" />
+  <joint name="base_link_2_steer_right_joint" type="revolute">
+    <origin xyz="0.3666 -0.108 0" rpy="0 0 0" />
+    <axis xyz="0 0 1" />
     <anchor xyz="0 0 0" />
     <parent link="base_link" />
-    <child link="front_right_axel_link" />
+    <child link="steer_right" />
     <limit lower="-${angle_limit}" upper="${angle_limit}" effort="9.6" velocity="5.3"/>
     <dynamics damping="0.2"/>
   </joint>
 
-  <transmission name="tran_front_right_axel">
+  <transmission name="tran_steer_right">
     <type>transmission_interface/SimpleTransmission</type>
-    <joint name="base_link_front_right_axel_joint">
+    <joint name="base_link_2_steer_right_joint">
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
     </joint>
-    <actuator name="front_right_axel_motor">
+    <actuator name="steer_right_motor">
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
       <mechanicalReduction>1</mechanicalReduction>
     </actuator>
   </transmission>
 
-  <link name="front_right_axel_link">
-    <inertial>
-      <mass value="0.001" />
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <inertia  ixx="0.00001" ixy="0.0" ixz="0.0"
-                iyy="0.00001" iyz="0.0"
-                izz="0.00001" />
-    </inertial>
-  </link>
-
-  <joint name="front_right_axel_front_right_wheel_joint" type="continuous">
-    <origin xyz="0.0 0.0 0" rpy="0 0 0" />
-    <axis xyz="0 0 1" />
-    <anchor xyz="0 0 0" />
-    <parent link="front_right_axel_link" />
-    <child link="front_right_wheel_link" />
-    <limit lower="-1000000000000.0" upper="1000000000000.0" effort="3.0" velocity="124"/>
-  </joint>
-
-  <transmission name="tran_front_right_wheel">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="front_right_axel_front_right_wheel_joint">
-      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="front_right_wheel_motor">
-      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator> 
-  </transmission>
-
-  <link name="front_right_wheel_link">
-    <inertial>
-      <mass value="1" />
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <inertia  ixx="0.0002946" ixy="0.0" ixz="0.0"
-                iyy="0.0002946" iyz="0.0"
-                izz="0.0004940" />
-    </inertial>
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/wheel.stl"/>
-      </geometry>
-      <material name="Black" />
-    </visual>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <cylinder radius="0.0315" length="${wheel_width}"/>
-      </geometry>
-    </collision>
-  </link>
+  <!-- ======= FRONT RIGHT ======= -->
+  <xacro:wheel name="front_right" parent="steer_right" direction="-1.0">
+    <origin xyz="0.0 0.0 0" rpy="1.5707 0 0" />
+  </xacro:wheel>
 
 </robot>
diff --git a/urdf/include/road_old/road.dae b/urdf/include/road_old/road.dae
deleted file mode 100644
index 18c3cd2894005e36c99f8443b42942ead98cf0e8..0000000000000000000000000000000000000000
--- a/urdf/include/road_old/road.dae
+++ /dev/null
@@ -1,122 +0,0 @@
-<?xml version="1.0" encoding="utf-8"?>
-<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
-  <asset><contributor><author></author><authoring_tool>FBX COLLADA exporter</authoring_tool><comments></comments></contributor><created>2014-10-05T08:59:28Z</created><keywords></keywords><modified>2014-10-05T08:59:28Z</modified><revision></revision><subject></subject><title></title><unit meter="0.025400" name="centimeter"></unit><up_axis>Y_UP</up_axis></asset>
-  <library_images>
-    <image id="Map #1-image" name="Map #1"><init_from>road.png</init_from></image>
-  </library_images>
-  <library_materials>
-    <material id="Material #36" name="Material #36">
-      <instance_effect url="#Material #36-fx"/>
-    </material>
-  </library_materials>
-  <library_effects>
-    <effect id="Material #36-fx" name="Material #36">
-      <profile_COMMON>
-        <technique sid="standard">
-          <phong>
-            <emission>
-              <color sid="emission">0.000000  0.000000 0.000000 1.000000</color>
-            </emission>
-            <ambient>
-              <color sid="ambient">1.000000  1.000000 1.000000 1.000000</color>
-            </ambient>
-            <diffuse>
-              <texture texture="Map #1-image" texcoord="CHANNEL0">
-                <extra>
-                  <technique profile="MAYA">
-                    <wrapU sid="wrapU0">TRUE</wrapU>
-                    <wrapV sid="wrapV0">TRUE</wrapV>
-                    <blend_mode>ADD</blend_mode>
-                  </technique>
-                </extra>
-              </texture>
-            </diffuse>
-            <specular>
-              <color sid="specular">0.000000  0.000000 0.000000 1.000000</color>
-            </specular>
-            <shininess>
-              <float sid="shininess">2.000000</float>
-            </shininess>
-            <reflective>
-              <color sid="reflective">0.000000  0.000000 0.000000 1.000000</color>
-            </reflective>
-            <reflectivity>
-              <float sid="reflectivity">1.000000</float>
-            </reflectivity>
-            <transparent opaque="RGB_ZERO">
-              <color sid="transparent">1.000000  1.000000 1.000000 1.000000</color>
-            </transparent>
-            <transparency>
-              <float sid="transparency">0.000000</float>
-            </transparency>
-          </phong>
-        </technique>
-      </profile_COMMON>
-    </effect>
-  </library_effects>
-  <library_geometries>
-    <geometry id="QR_Code-lib" name="QR_CodeMesh">
-      <mesh>
-        <source id="QR_Code-POSITION">
-          <float_array id="QR_Code-POSITION-array" count="12">
--3.149606 -3.149606 0.000000
-3.149606 -3.149606 0.000000
--3.149606 3.149606 0.000000
-3.149606 3.149606 0.000000
-</float_array>
-          <technique_common>
-            <accessor source="#QR_Code-POSITION-array" count="4" stride="3">
-              <param name="X" type="float"/>
-              <param name="Y" type="float"/>
-              <param name="Z" type="float"/>
-            </accessor>
-          </technique_common>
-        </source>
-        <source id="QR_Code-Normal0">
-          <float_array id="QR_Code-Normal0-array" count="18">
-0.000000 0.000000 1.000000
-0.000000 0.000000 1.000000
-0.000000 0.000000 1.000000
-0.000000 0.000000 1.000000
-0.000000 0.000000 1.000000
-0.000000 0.000000 1.000000
-</float_array>
-          <technique_common>
-            <accessor source="#QR_Code-Normal0-array" count="6" stride="3">
-              <param name="X" type="float"/>
-              <param name="Y" type="float"/>
-              <param name="Z" type="float"/>
-            </accessor>
-          </technique_common>
-        </source>
-        <source id="QR_Code-UV0">
-          <float_array id="QR_Code-UV0-array" count="8">
-0.000499 0.000500
-0.999500 0.000499
-0.000500 0.999501
-0.999501 0.999500
-</float_array>
-          <technique_common>
-            <accessor source="#QR_Code-UV0-array" count="4" stride="2">
-              <param name="S" type="float"/>
-              <param name="T" type="float"/>
-            </accessor>
-          </technique_common>
-        </source>
-        <vertices id="QR_Code-VERTEX">
-          <input semantic="POSITION" source="#QR_Code-POSITION"/>
-        </vertices>
-        <triangles count="2" material="Material #36"><input semantic="VERTEX" offset="0" source="#QR_Code-VERTEX"/><input semantic="NORMAL" offset="1" source="#QR_Code-Normal0"/><input semantic="TEXCOORD" offset="2" set="0" source="#QR_Code-UV0"/><p> 0 0 0 1 1 1 3 2 3 3 3 3 2 4 2 0 5 0</p></triangles>
-      </mesh>
-    </geometry>
-  </library_geometries>
-  <library_visual_scenes>
-    <visual_scene id="" name="">
-      <node name="QR_Code" id="QR_Code" sid="QR_Code"><matrix sid="matrix">1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.000000</matrix><instance_geometry url="#QR_Code-lib"><bind_material><technique_common><instance_material symbol="Material #36" target="#Material #36"/></technique_common></bind_material></instance_geometry><extra><technique profile="FCOLLADA"><visibility>1.000000</visibility></technique></extra></node>
-      <extra><technique profile="MAX3D"><frame_rate>30.000000</frame_rate></technique><technique profile="FCOLLADA"><start_time>0.000000</start_time><end_time>3.333333</end_time></technique></extra>
-    </visual_scene>
-  </library_visual_scenes>
-  <scene>
-    <instance_visual_scene url="#"></instance_visual_scene>
-  </scene>
-</COLLADA>
diff --git a/urdf/include/road_old/road.gazebo b/urdf/include/road_old/road.gazebo
deleted file mode 100644
index dac7e641bb1944ffc602cb248b30cd9392050a3a..0000000000000000000000000000000000000000
--- a/urdf/include/road_old/road.gazebo
+++ /dev/null
@@ -1,32 +0,0 @@
-<?xml version="2.0"?>
-<robot>
-
-  <gazebo>
-    <static>1</static>
-  </gazebo>
-    
-  <gazebo reference="road_link">
-    <material>Gazebo/Grey</material>
-  </gazebo>
-
-  <gazebo reference="road_image">
-  </gazebo>
-
-  <gazebo reference="ceiling">
-    <material>Gazebo/Grey</material>
-  </gazebo>
-
-  <gazebo reference="lamp1">
-    <material>Gazebo/Red</material>
-  </gazebo>
-
-  <gazebo reference="lamp2">
-    <material>Gazebo/Green</material>
-  </gazebo>
-
-  <gazebo reference="lamp3">
-    <material>Gazebo/Blue</material>
-  </gazebo>
-
-</robot>
-
diff --git a/urdf/include/road_old/road.png b/urdf/include/road_old/road.png
deleted file mode 100644
index 8a7400d1844bc8a407e1f87e64832c1d54270e0b..0000000000000000000000000000000000000000
Binary files a/urdf/include/road_old/road.png and /dev/null differ
diff --git a/urdf/include/road_old/road.xacro b/urdf/include/road_old/road.xacro
deleted file mode 100644
index 5c614a0bfc4535cdb755f3a81fa868f06e131312..0000000000000000000000000000000000000000
--- a/urdf/include/road_old/road.xacro
+++ /dev/null
@@ -1,143 +0,0 @@
-<?xml version="1.0"?>
-
-<root xmlns:xacro="http://ros.org/wiki/xacro">
-
-  <xacro:macro name="road" params="name size *origin">
-    <!-- obstacle -->
-    <link name="road_link">
-      <inertial>
-        <mass value="100"/>
-        <origin xyz="0 0 0.01" 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"/>
-        <geometry>
-          <box size="10 10 0.02"/>
-        </geometry>
-        <material name="green"/>
-      </visual>
-      <collision>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <box size="10 10 0.02"/>
-        </geometry>
-      </collision>
-    </link>
-
-    <joint name="road_link_road_image" type="fixed">
-      <origin xyz="0 0 0.011" rpy="1.5707 0 0" />
-      <parent link="road_link"/>
-      <child link="road_image" />
-    </joint>
-
-    <link name="road_image">
-      <inertial>
-        <mass value="0.001"/>
-        <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-        <inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
-      </inertial>
-      <visual>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <mesh filename="package://model_car_description/urdf/include/road/road.dae" scale="${size*8.63} ${size*8.63} ${size*8.63}"/>
-        </geometry>
-      </visual>
-      <collision>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <mesh filename="package://model_car_description/urdf/include/road/road.dae" scale="${size*8.63} ${size*8.63} ${size*8.63}"/>
-        </geometry>
-      </collision>
-    </link>
-
-    <joint name="road_link_ceiling" type="fixed">
-      <origin xyz="0 0 2.0" rpy="0 0 0" />
-      <parent link="road_link"/>
-      <child link="ceiling" />
-    </joint>
-
-    <link name="ceiling">
-    </link>
-
-    <joint name="ceiling_lamp1" type="fixed">
-      <origin xyz="10 10 -0.02" rpy="0 0 0" />
-      <parent link="ceiling"/>
-      <child link="lamp1" />
-    </joint>
-
-    <link name="lamp1">
-      <inertial>
-        <mass value="0.001"/>
-        <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-        <inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
-      </inertial>
-      <visual>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <box size="2 2 0.02"/>
-        </geometry>
-      </visual>
-      <collision>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <box size="2 2 0.02"/>
-        </geometry>
-      </collision>
-    </link>
-
-    <joint name="ceiling_lamp2" type="fixed">
-      <origin xyz="10 -10 -0.02" rpy="0 0 0" />
-      <parent link="ceiling"/>
-      <child link="lamp2" />
-    </joint>
-
-    <link name="lamp2">
-      <inertial>
-        <mass value="0.001"/>
-        <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-        <inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
-      </inertial>
-      <visual>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <box size="2 2 0.02"/>
-        </geometry>
-      </visual>
-      <collision>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <box size="2 2 0.02"/>
-        </geometry>
-      </collision>
-    </link>
-
-    <joint name="ceiling_lamp3" type="fixed">
-      <origin xyz="-10 10 -0.02" rpy="0 0 0" />
-      <parent link="ceiling"/>
-      <child link="lamp3" />
-    </joint>
-
-    <link name="lamp3">
-      <inertial>
-        <mass value="0.001"/>
-        <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-        <inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
-      </inertial>
-      <visual>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <box size="2 2 0.02"/>
-        </geometry>
-      </visual>
-      <collision>
-        <origin xyz="0 0 0" rpy="0 0 0"/>
-        <geometry>
-          <box size="2 2 0.02"/>
-        </geometry>
-      </collision>
-    </link>
-  </xacro:macro>
-
-</root>
-
diff --git a/urdf/include/road_old/road_env.xacro b/urdf/include/road_old/road_env.xacro
deleted file mode 100755
index f51ed6d35b34a159a58b41eb3ce902cd65d8d7cd..0000000000000000000000000000000000000000
--- a/urdf/include/road_old/road_env.xacro
+++ /dev/null
@@ -1,10 +0,0 @@
-<!-- -->
-<robot name="road" xmlns:xacro="http://www.ros.org/wiki/xacro">
- 
-  <xacro:include filename="$(find model_car_description)/urdf/include/road/road.xacro" />
-  <xacro:include filename="$(find model_car_description)/urdf/include/road/road.gazebo" />
-
-  <xacro:road name="road" size="5.0">
-    <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-  </xacro:road>
-</robot>
diff --git a/urdf/include/sensors.gazebo b/urdf/include/sensors.gazebo
deleted file mode 100644
index acdf8007b50eb7e846dd037dceab8f287ef0eec0..0000000000000000000000000000000000000000
--- a/urdf/include/sensors.gazebo
+++ /dev/null
@@ -1,17 +0,0 @@
-<?xml version="2.0"?>
-<robot>
-  <gazebo>
-    <static>0</static>
-  </gazebo>
-
-  <gazebo reference="sensor_board">
-    <material>Gazebo/Grey</material>
-  </gazebo>
-
-  <gazebo reference="camera_board">
-    <material>Gazebo/Grey</material>
-  </gazebo>
-  
-  <!-- each sensors included separately -->
-
-</robot>
diff --git a/urdf/include/sensors.xacro b/urdf/include/sensors.xacro
index edf91350515b72d54c951ce8ba33ad75c3857342..ae8f0ee5062c78af0a10e35c016eb0b8235a9e53 100644
--- a/urdf/include/sensors.xacro
+++ b/urdf/include/sensors.xacro
@@ -1,213 +1,49 @@
 <?xml version="1.0"?>
 
-<robot name="model_car" xmlns:xacro="http://www.ros.org/wiki/xacro">
+<robot name="model_car" xmlns:xacro="http://ros.org/wiki/xacro">
 
   <!-- Included URDF Files -->
+  <xacro:include filename="$(find iri_rplidar_laser2d_description)/urdf/rplidar_laser2d.xacro" />  
+  <xacro:include filename="$(find iri_hcsr04_sonar_description)/urdf/hc_sr04_sonar.xacro" />
+  <xacro:include filename="$(find iri_mpu9250_imu_description)/urdf/mpu9250_imu.xacro" />
+  <xacro:include filename="$(find iri_uvc_camera_description)/urdf/uvc_camera.xacro" />
   
   <xacro:property name="PI" value="3.1415926535897931" />
 
-  <link name="sensor_board">
-    <inertial>
-      <mass value="6" />
-      <origin xyz="0.12043628 0.00000000 0.00171950" rpy="0 0 0"/>
-      <inertia ixx="0.0123739" ixy="0.0" ixz="0.0003463"
-               iyy="0.0711051" iyz="0.0" 
-               izz="0.0820107" />
-    </inertial>
-    <visual>
-      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/sensor_board.stl" />
-      </geometry>
-      <material name="Grey" />
-    </visual>
-    <collision>
-      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/sensor_board.stl" />
-      </geometry>
-    </collision>
-  </link>
+  <xacro:rplidar_laser2d name="front_lidar" prefix="model_car" parent="base_link">
+    <origin xyz="0.439 0.0 0.05" rpy="0 ${PI} ${PI}" />
+  </xacro:rplidar_laser2d>
 
-  <joint name="joint_base_link_to_sensor_board" type="fixed" >
-    <parent link="base_link"/>
-    <child link="sensor_board"/>
-    <origin xyz="0 0 0.0415" rpy="0 0 0"/>
-  </joint>
+  <xacro:hcsr04_sonar name="side_left" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
+    <origin xyz="0.2585 0.1107 0.0" rpy="-${PI/2.0} ${PI/2.0} 0" />
+  </xacro:hcsr04_sonar>
 
-  <link name="camera_board">
-    <inertial>
-      <mass value="0.6000000" />
-      <origin xyz="0.04901990 0.00000000 0.00000000" rpy="0 0 0"/>
-      <inertia ixx="0.0003816" ixy="0.0" ixz="0.0"
-               iyy="0.0003420" iyz="0.0" 
-               izz="0.0007211" />
-    </inertial>
-    <visual>
-      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/camera_board.stl" />
-      </geometry>
-      <material name="Grey" />
-    </visual>
-    <collision>
-      <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/camera_board.stl" />
-      </geometry>
-    </collision>
-  </link>
+  <xacro:hcsr04_sonar name="side_right" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
+    <origin xyz="0.2585 -0.1107 0.0" rpy="${PI/2.0} ${PI/2.0} 0" />
+  </xacro:hcsr04_sonar>
 
-  <joint name="joint_sensor_board_to_camera_board" type="fixed" >
-    <parent link="sensor_board"/>
-    <child link="camera_board"/>
-    <origin xyz="0.109 0 0.105" rpy="0 0 0"/>
-  </joint>
+  <xacro:hcsr04_sonar name="rear_center" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
+    <origin xyz="-0.0882 0.0 0.0" rpy="${PI} ${PI/2.0} 0" />
+  </xacro:hcsr04_sonar>
 
-  <!--*************************************************-->
-  <!--*               Sensors                         *-->
-  <!--*************************************************-->
+  <xacro:hcsr04_sonar name="rear_left" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
+    <origin xyz="-0.07912 0.09898 0.0" rpy="${PI+PI/6.0} ${PI/2.0} 0" />
+  </xacro:hcsr04_sonar>
 
-  <!-- IMU -->
-  <link name="imu">
-    <inertial>
-      <mass value="0.0200000" />
-      <origin xyz="0.00000000 0.00000000 0.00150000" rpy="0 0 0"/>
-      <inertia ixx="0.0000007" ixy="0.0" ixz="0.0"
-               iyy="0.0000004" iyz="0.0" 
-               izz="0.0000011" />
-    </inertial>
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/IMU.stl" />
-      </geometry>
-      <material name="Black" />
-    </visual>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/IMU.stl" />
-      </geometry>
-    </collision>
-  </link>
+  <xacro:hcsr04_sonar name="rear_right" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
+    <origin xyz="-0.07912 -0.09898 0.0" rpy="${PI-PI/6.0} ${PI/2.0} 0" />
+  </xacro:hcsr04_sonar>
 
-  <joint name="joint_sensor_board_to_imu" type="fixed" >
-    <parent link="sensor_board"/>
-    <child link="imu"/>
-    <origin xyz="0.239 0.02 0.0025" rpy="0 0 ${PI/2}"/>
-  </joint>
+  <xacro:mpu9250_imu name="imu" parent="base_link" sim_config="$(find iri_imu_gazebo)/config/mpu9250_imu_sim_config.yaml">
+    <origin xyz="0.006 0.0 0.0271" rpy="0 0 0" />
+  </xacro:mpu9250_imu>
 
-  <!-- RP_LIDAR -->
-  <link name="laser">
-    <inertial>
-      <mass value="1.8362923" />
-      <origin xyz="0.0000000 0.0000000 -0.01040000" rpy="0 0 0"/>
-      <inertia ixx="0.0009124" ixy="0.0" ixz="0.0"
-               iyy="0.0009124" iyz="0.0" 
-               izz="0.0013154" />
-    </inertial>
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/RP-LIDAR.stl" />
-      </geometry>
-      <material name="Black" />
-    </visual>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/RP-LIDAR.stl" />
-      </geometry>
-    </collision>
-  </link>
+  <xacro:uvc_camera name="front_camera" parent="base_link" resolution="low_res" model="basler" sim_config="$(find iri_camera_gazebo)/config/camera_sim_config.yaml">
+    <origin xyz="0.273 0.0 0.180" rpy="0 0 0" />
+  </xacro:uvc_camera>
 
-  <joint name="joint_sensor_board_to_laser" type="fixed" >
-    <parent link="sensor_board"/>
-    <child link="laser"/>
-    <origin xyz="0.10445 0 0.0333" rpy="0 0 -${PI}"/>
-  </joint>
-
-  <!-- top camera -->
-<!--  <xacro:property name="top_camera_name" value="top_camera" />-->
-  
-  <link name="top_camera">
-    <inertial>
-      <mass value="0.1600000" />
-      <origin xyz="0.00000000 0.00000000 -0.01396703" rpy="0 0 0"/>
-      <inertia ixx="0.0000170" ixy="0.0" ixz="0.0"
-               iyy="0.0000170" iyz="0.0" 
-               izz="0.0000183" />
-    </inertial>
-    <visual>
-      <origin xyz="0 0 0" rpy="0 ${PI/2} 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/gps_camera.stl" />
-      </geometry>
-      <material name="Black" />
-    </visual>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 ${PI/2} 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/gps_camera.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <joint name="joint_camera_board_to_top_camera" type="fixed" >
-    <parent link="camera_board"/>
-    <child link="top_camera"/>
-    <origin xyz="0.019 0 0.0405" rpy="0 -${PI/2} ${PI}"/>
-  </joint>
-
-  <link name="top_camera_optical">
-  </link>
-
-  <joint name="joint_top_camera_to_top_camera_optical" type="fixed" >
-    <parent link="top_camera"/>
-    <child link="top_camera_optical"/>
-    <origin xyz="0.0 0 0.0" rpy="-${PI/2} 0 -${PI/2}"/>
-  </joint>
-
-  <!-- front camera -->
-  <xacro:property name="front_camera_name" value="camera" />
-  
-  <link name="${front_camera_name}_link">
-    <inertial>
-      <mass value="1.3000000" />
-      <origin xyz="0.00000000 0.00000000 -0.01150000" rpy="0 0 0"/>
-      <inertia ixx="0.0017500" ixy="0.0" ixz="0.0"
-               iyy="0.0001146" iyz="0.0" 
-               izz="0.0017500" />
-    </inertial>
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/creative_camera.stl" />
-      </geometry>
-      <material name="Black" />
-    </visual>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://model_car_description/meshes/creative_camera.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <joint name="joint_camera_board_to_${front_camera_name}_link" type="fixed" >
-    <parent link="camera_board"/>
-    <child link="${front_camera_name}_link"/>
-    <origin xyz="0.119 0 0.0" rpy="0 0 0"/>
-  </joint>
-  
-  <link name="${front_camera_name}_rgb_optical_frame">
-  </link>
-
-  <joint name="joint_${front_camera_name}_link_to_${front_camera_name}_rgb_optical_frame" type="fixed" >
-    <parent link="${front_camera_name}_link"/>
-    <child link="${front_camera_name}_rgb_optical_frame"/>
-    <origin xyz="0 0 0" rpy="-${PI/2} 0 -${PI/2}"/>
-  </joint>
+  <xacro:uvc_camera name="rear_camera" parent="base_link" resolution="low_res" model="delock" sim_config="$(find iri_camera_gazebo)/config/camera_sim_config.yaml">
+    <origin xyz="-0.0112 0.0 0.055" rpy="0 0 ${PI}" />
+  </xacro:uvc_camera>
 
 </robot>
diff --git a/urdf/include/sensors/front_rgb_camera.gazebo b/urdf/include/sensors/front_rgb_camera.gazebo
deleted file mode 100644
index a5e932dab2424a505961d1b9db3008592e31e4aa..0000000000000000000000000000000000000000
--- a/urdf/include/sensors/front_rgb_camera.gazebo
+++ /dev/null
@@ -1,39 +0,0 @@
-<?xml version="2.0"?>
-<robot>
-
-  <property name="front_camera_name" value="camera" />
-  <property name="rate" value="5.0" />
-
-  <gazebo reference="${front_camera_name}_link">
-    <sensor type="camera" name="${front_camera_name}">
-      <update_rate>${rate}</update_rate>
-      <camera name="${front_camera_name}">
-        <horizontal_fov>1.24</horizontal_fov>
-        <image>
-          <width>640</width>
-          <height>480</height>
-          <format>R8G8B8</format>
-        </image>
-        <clip>
-          <near>0.2</near>
-          <far>15.0</far>
-        </clip>
-        <noise>
-          <type>gaussian</type>
-          <mean>0.0</mean>
-          <stddev>0.007</stddev>
-        </noise>
-      </camera>
-      <plugin name="${front_camera_name}_controller" filename="libgazebo_ros_camera.so">
-        <alwaysOn>true</alwaysOn>
-        <updateRate>${rate}</updateRate>
-        <cameraName>${front_camera_name}</cameraName>
-        <imageTopicName>rgb/image_raw</imageTopicName>
-        <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
-        <frameName>${front_camera_name}_rgb_optical_frame</frameName>
-        <hackBaseline>0.07</hackBaseline>
-      </plugin>
-    </sensor>
-  </gazebo>
-
-</robot>
diff --git a/urdf/include/sensors/front_rgbd_camera.gazebo b/urdf/include/sensors/front_rgbd_camera.gazebo
deleted file mode 100644
index ab5cc1a91e3d0a0da9f3facfbc2a8f1cbe36640d..0000000000000000000000000000000000000000
--- a/urdf/include/sensors/front_rgbd_camera.gazebo
+++ /dev/null
@@ -1,73 +0,0 @@
-<?xml version="2.0"?>
-<robot>
-
-  <property name="front_camera_name" value="camera" />
-  <property name="rate" value="5.0" />
-  
-  <gazebo reference="${front_camera_name}_link">
-    <material>Gazebo/Black</material>
-  </gazebo>
-
-  <gazebo reference="${front_camera_name}_rgb_optical_frame">
-    <material>Gazebo/Black</material>
-  </gazebo>
-
-  <gazebo reference="${front_camera_name}_link">
-    <sensor type="depth" name="${front_camera_name}">       
-      <always_on>1</always_on>
-      <visualize>true</visualize>
-      <update_rate>${rate}</update_rate>
-      <camera>
-        <horizontal_fov>0.83</horizontal_fov>  
-        <image>
-          <width>640</width>
-          <height>480</height>
-          <format>R8G8B8</format>
-        </image>
-        <depth_camera>
-        </depth_camera>
-        <clip>
-          <near>0.2</near>
-          <far>50.0</far>
-        </clip>
-        <!--
-        <distortion>
-          <k1>-0.25</k1>
-          <k2>0.12</k2>
-          <k3>0.0</k3>
-          <p1>-0.00028</p1>
-          <p2>-0.00005</p2>
-        </distortion>
-        -->
-        <noise>
-          <type>gaussian</type>
-          <mean>0.0</mean>
-          <stddev>0.007</stddev>
-        </noise>
-      </camera>
-      <plugin name="${front_camera_name}_controller" filename="libgazebo_ros_openni_kinect.so">
-        <alwaysOn>true</alwaysOn>
-        <updateRate>${rate}</updateRate>
-        <cameraName>${front_camera_name}</cameraName>
-        <frameName>${front_camera_name}_rgb_optical_frame</frameName>                   
-        <imageTopicName>rgb/image_raw</imageTopicName>
-        <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
-        <depthImageTopicName>depth/image_raw</depthImageTopicName>
-        <pointCloudTopicName>depth/points</pointCloudTopicName>
-        <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>            
-        <pointCloudCutoff>0.4</pointCloudCutoff>                
-        <hackBaseline>0.007</hackBaseline>
-        <CxPrime>0.0</CxPrime>
-        <Cx>0.0</Cx>
-        <Cy>0.0</Cy>
-        <focalLength>0.0</focalLength>
-        <noise>
-          <type>gaussian</type>
-          <mean>0.0</mean>
-          <stddev>0.01</stddev>
-        </noise>
-      </plugin>
-    </sensor>
-  </gazebo>
-
-</robot>
diff --git a/urdf/include/sensors/imu.gazebo b/urdf/include/sensors/imu.gazebo
deleted file mode 100644
index 82f564f97fcf10151e045a85f9d110dcb1443e19..0000000000000000000000000000000000000000
--- a/urdf/include/sensors/imu.gazebo
+++ /dev/null
@@ -1,28 +0,0 @@
-<?xml version="2.0"?>
-<robot>
-
-  <!-- IMU -->
-  <gazebo reference="imu">
-    <material>Gazebo/Black</material>
-  </gazebo>
-
-  <gazebo>
-    <plugin name="model_car_imu" filename="libhector_gazebo_ros_imu.so">
-      <updateRate>20.0</updateRate>
-      <robotNamespace>/</robotNamespace>
-      <bodyName>imu</bodyName>
-      <frameId>imu</frameId>
-      <topicName>imu</topicName>
-      <accelOffset>0 0 0</accelOffset>
-      <accelDrift>0.5 0.5 0.5</accelDrift>
-      <accelGaussianNoise>0.35 0.35 0.3</accelGaussianNoise>
-      <rateOffset>0 0 0</rateOffset>
-      <rateDrift>0.0 0.0 0.0</rateDrift>
-      <rateGaussianNoise>0.005 0.005 0.0015</rateGaussianNoise>
-      <headingOffset>0</headingOffset>
-      <headingDrift>0.1</headingDrift>
-      <headingGaussianNoise>0.05</headingGaussianNoise>
-    </plugin>
-  </gazebo>
-
-</robot>
diff --git a/urdf/include/sensors/laser.gazebo b/urdf/include/sensors/laser.gazebo
deleted file mode 100644
index e93cab5cc75cddd03a704a1b61e2bff8dae42d70..0000000000000000000000000000000000000000
--- a/urdf/include/sensors/laser.gazebo
+++ /dev/null
@@ -1,40 +0,0 @@
-<?xml version="2.0"?>
-<robot>
-
-  <!-- RP-LIDAR -->
-  <gazebo reference="laser">
-    <material>Gazebo/Black</material>
-  </gazebo>
-
-  <gazebo reference="laser">
-    <sensor type="ray" name="rp_lidar_sensor">
-      <pose>0 0 0 0 0 0</pose>
-      <visualize>false</visualize>
-      <update_rate>10</update_rate>
-      <ray>
-        <scan>
-          <horizontal>
-            <samples>400</samples>
-            <min_angle>-3.14159</min_angle>
-            <max_angle>3.14159</max_angle>
-          </horizontal>
-        </scan>
-        <range>
-          <min>0.15</min>
-          <max>6.0</max>
-          <resolution>0.05</resolution>
-        </range>
-        <noise>
-          <type>gaussian</type>
-          <mean>0.0</mean>
-          <stddev>0.01</stddev>
-        </noise>
-      </ray>
-      <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
-        <topicName>/scan</topicName>
-        <frameName>laser</frameName>
-      </plugin>
-    </sensor>
-  </gazebo>
-
-</robot>
diff --git a/urdf/include/sensors/top_camera.gazebo b/urdf/include/sensors/top_camera.gazebo
deleted file mode 100644
index e26162848f40998fa78dddf21b0f7ef89123a85a..0000000000000000000000000000000000000000
--- a/urdf/include/sensors/top_camera.gazebo
+++ /dev/null
@@ -1,55 +0,0 @@
-<?xml version="2.0"?>
-<robot>
-
-  <property name="top_camera_name" value="top_camera" />
-  <property name="rate" value="5.0" />
-
-  <gazebo reference="${top_camera_name}">
-    <material>Gazebo/Black</material>
-  </gazebo>
-
-  <gazebo reference="${top_camera_name}_optical">
-    <material>Gazebo/Black</material>
-  </gazebo>
-
-  <gazebo reference="${top_camera_name}">
-    <!-- -->
-    <sensor type="wideanglecamera" name="${top_camera_name}">
-      <camera>
-        <horizontal_fov>3.14</horizontal_fov>
-        <image>
-          <width>1920</width>
-          <height>1080</height>
-        </image>
-        <clip>
-          <near>0.1</near>
-          <far>100</far>
-        </clip>
-        <lens>
-          <type>stereographic</type>
-          <scale_to_hfov>true</scale_to_hfov>
-          <cutoff_angle>1.5707</cutoff_angle>
-          <env_texture_size>512</env_texture_size>
-        </lens>
-      </camera>
-      <always_on>1</always_on>
-      <update_rate>${rate}</update_rate>
-      <plugin name="${top_camera_name}_controller" filename="libgazebo_ros_camera.so">
-        <alwaysOn>true</alwaysOn>
-        <updateRate>${rate}</updateRate>
-        <cameraName>usb_cam</cameraName>
-        <imageTopicName>image_raw</imageTopicName>
-        <cameraInfoTopicName>camera_info</cameraInfoTopicName>
-        <frameName>${top_camera_name}_optical</frameName>
-        <hackBaseline>0.07</hackBaseline>
-        <distortionK1>-0.241471</distortionK1>
-        <distortionK2>0.038162</distortionK2>
-        <distortionK3>0.000000</distortionK3>
-        <distortionT1>0.005967</distortionT1>
-        <distortionT2>-0.002110</distortionT2>
-      </plugin>
-    </sensor>
-    
-  </gazebo>
-
-</robot>
diff --git a/urdf/include/wheel.gazebo b/urdf/include/wheel.gazebo
new file mode 100644
index 0000000000000000000000000000000000000000..6df0434111d5fb04ebc8da2378a72d4b8cf1b530
--- /dev/null
+++ b/urdf/include/wheel.gazebo
@@ -0,0 +1,24 @@
+<?xml version="1.0"?>
+<root xmlns:xacro="http://ros.org/wiki/xacro">
+
+  <xacro:macro name="wheel_gazebo" params=" name">
+
+    <gazebo reference="${name}_wheel">
+      <gravity>true</gravity>
+      <self_collide>false</self_collide>
+      <material>Gazebo/Black</material>
+      <dampingFactor>0.0002</dampingFactor>
+      <mu1>0.300000</mu1>
+      <mu2>1.000000</mu2>
+<!--      <kp>50000000.0</kp>-->
+<!--      <kd>1.0</kd>-->
+    </gazebo>
+
+    <gazebo reference="${parent}_2_${name}_wheel">
+      <implicitSpringDamper>true</implicitSpringDamper>
+      <stopCfm>0.0</stopCfm>
+      <stopErp>0.0</stopErp>
+    </gazebo>
+  </xacro:macro>
+</root>
+
diff --git a/urdf/include/wheel.xacro b/urdf/include/wheel.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..43132f0b589f059a111f8a62ccf3064a89fd48e1
--- /dev/null
+++ b/urdf/include/wheel.xacro
@@ -0,0 +1,57 @@
+<?xml version="1.0"?>
+
+<root xmlns:xacro="http://ros.org/wiki/xacro">
+
+  <xacro:include filename="$(find model_car_description)/urdf/include/wheel.gazebo" />
+
+  <xacro:macro name="wheel" params="name parent direction *origin">
+    <link name="${name}_wheel">
+      <visual>
+        <origin xyz="0 0 0" rpy="0 0 0"/>
+        <geometry>
+          <mesh filename="package://model_car_description/meshes/wheel.stl"/>
+        </geometry>
+        <material name="Black">
+          <color rgba="0.1 0.1 0.1 1.0"/>
+        </material>
+      </visual>
+      <inertial>
+        <mass value="0.25918139" />
+        <origin xyz="0.00000000 0.00000000 0.00000000" rpy="0 0 0"/>
+        <inertia ixx="0.00018551" ixy="0.00000000" ixz="0.00000000" 
+                 iyy="0.00018551" iyz="0.00000000" 
+                 izz="0.00032398" />
+      </inertial>
+      <collision>
+        <origin xyz="0 0 0" rpy="0 0 0"/>
+        <geometry>
+          <mesh filename="package://model_car_description/meshes/wheel.stl"/>
+        </geometry>
+      </collision>
+    </link>
+
+    <joint name="${parent}_2_${name}_wheel" type="continuous">
+      <xacro:insert_block name="origin" />
+      <parent link="${parent}"/>
+      <child link="${name}_wheel"/>
+      <axis xyz="0 0 ${direction}"/>
+      <limit effort="10000" velocity="10.0"/>
+    </joint>
+
+    <transmission name="${name}_tran">
+      <type>transmission_interface/SimpleTransmission</type>
+      <joint name="${parent}_2_${name}_wheel">
+        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+      </joint>
+      <actuator name="${name}_motor">
+        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        <mechanicalReduction>1</mechanicalReduction>
+      </actuator>
+    </transmission>
+
+    <xacro:wheel_gazebo name="${name}"/>
+
+  </xacro:macro>
+
+</root>
+