diff --git a/config/pan_tilt_xacro.yaml b/config/pan_tilt_xacro.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..31174bf6387f4e3752f30ec42a0316e3af7411af
--- /dev/null
+++ b/config/pan_tilt_xacro.yaml
@@ -0,0 +1,6 @@
+parent: world
+pan_joint_name: pan
+tilt_joint_name: tilt
+load_name: camera_base_frame
+joint_interface: EffortJointInterface
+
diff --git a/urdf/pan_tilt.xacro b/urdf/pan_tilt.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..306844b1faae9bc3df68be69b31a76573ffa09e9
--- /dev/null
+++ b/urdf/pan_tilt.xacro
@@ -0,0 +1,112 @@
+<?xml version="1.0"?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:include filename="$(find iri_dynamixel_pan_tilt_gazebo)/urdf/pan_tilt.gazebo"/>
+
+  <xacro:macro name="pan_tilt" params="parent pan_joint_name tilt_joint_name load_name joint_interface sim_config *origin">
+
+    <link name="${pan_joint_name}_frame">
+      <visual>
+        <origin rpy="0 0 0" xyz="-.016 0 0.02"/>
+        <geometry>
+          <box size=".054 .032 .04"/>
+        </geometry>
+        <material name="black">
+          <color rgba="0 0 0 1"/>
+        </material>
+      </visual>
+      <inertial>
+        <origin rpy="0 0 0" xyz="-.016 0 0.02"/>
+        <mass value="1"/>
+        <inertia 
+          ixx="0.0001" ixy="0.0" ixz="0.0" 
+          iyy="0.0001" iyz="0.0" 
+          izz="0.0001"/>
+      </inertial>
+      <collision>
+        <origin rpy="0 0 0" xyz="-.016 0 0.02"/>
+        <geometry>
+          <box size=".054 .032 .04"/>
+        </geometry>
+      </collision>
+    </link>
+
+    <link name="${tilt_joint_name}_frame">
+      <visual>
+        <origin rpy="0 0 -${pi/2}" xyz="0 0 .027"/>
+        <geometry>
+          <box size=".032 .04 .054"/>
+        </geometry>
+        <material name="green">
+          <color rgba="0 .8 0 1"/>
+        </material>
+      </visual>
+      <inertial>
+        <origin rpy="0 0 -${pi/2}" xyz="0 0 .027"/>
+        <mass value="1"/>
+        <inertia 
+          ixx="0.0001" ixy="0.0" ixz="0.0" 
+          iyy="0.0001" iyz="0.0" 
+          izz="0.0001"/>
+      </inertial>
+      <collision>
+        <origin rpy="0 0 -${pi/2}" xyz="0 0 .027"/>
+        <geometry>
+          <box size=".032 .04 .054"/>
+        </geometry>
+      </collision>
+    </link>
+
+    <joint name="joint_${parent}_to_${pan_joint_name}_frame" type="fixed" >
+      <parent link="${parent}"/>
+      <child link="${pan_joint_name}_frame"/>
+      <xacro:insert_block name="origin" />
+    </joint>
+
+
+    <joint name="${pan_joint_name}" type="revolute" >
+      <parent link="${pan_joint_name}_frame"/>
+      <child link="${tilt_joint_name}_frame"/>
+      <axis xyz="0 0 1"/>
+      <origin rpy="0 0 ${pi/2}" xyz="0 0 0.04"/>
+      <limit effort="25.0" lower="${radians(-90)}" upper="${radians(90)}" velocity="0.5"/>
+      <dynamics damping="0.5"/>
+    </joint>
+
+    <transmission name="${pan_joint_name}_trans">
+      <type>transmission_interface/SimpleTransmission</type>
+      <joint name="${pan_joint_name}">
+        <hardwareInterface>hardware_interface/${joint_interface}</hardwareInterface>
+      </joint>
+      <actuator name="${pan_joint_name}_motor">
+        <hardwareInterface>hardware_interface/${joint_interface}</hardwareInterface>
+        <mechanicalReduction>1</mechanicalReduction>
+      </actuator>
+    </transmission>
+
+    <joint name="${tilt_joint_name}" type="revolute" >
+      <parent link="${tilt_joint_name}_frame"/>
+      <child link="${load_name}"/>
+      <axis xyz="0 0 1"/>
+      <origin rpy="${pi/2} 0 ${pi/2}" xyz="0.02 0 0.0425"/>
+      <limit effort="25.0" lower="${radians(-90)}" upper="${radians(90)}" velocity="0.5"/>
+      <dynamics damping="0.5"/>
+    </joint>
+
+    <transmission name="${tilt_joint_name}_trans">
+      <type>transmission_interface/SimpleTransmission</type>
+      <joint name="${tilt_joint_name}">
+        <hardwareInterface>hardware_interface/${joint_interface}</hardwareInterface>
+      </joint>
+      <actuator name="${tilt_joint_name}_motor">
+        <hardwareInterface>hardware_interface/${joint_interface}</hardwareInterface>
+        <mechanicalReduction>1</mechanicalReduction>
+      </actuator>
+    </transmission>
+
+    <xacro:pan_tilt_gazebo pan_joint_name="${pan_joint_name}" tilt_joint_name="${tilt_joint_name}" sim_config="${sim_config}"/>
+
+  </xacro:macro>
+
+</robot>