From 68de5fa7b7d4cfe82a6681c8d0c780376744c760 Mon Sep 17 00:00:00 2001
From: Alopez <alopez@iri.upc.edu>
Date: Tue, 14 Apr 2020 16:19:28 +0200
Subject: [PATCH] Included a first version of the pan and tilt to check that
 all is working

---
 config/ana_pan_tilt_xacro.yaml |  5 ++++
 package.xml                    |  1 +
 urdf/include/sensors.xacro     | 42 ++++++++++++++++++++++++++++++++++
 3 files changed, 48 insertions(+)
 create mode 100644 config/ana_pan_tilt_xacro.yaml

diff --git a/config/ana_pan_tilt_xacro.yaml b/config/ana_pan_tilt_xacro.yaml
new file mode 100644
index 0000000..82c8193
--- /dev/null
+++ b/config/ana_pan_tilt_xacro.yaml
@@ -0,0 +1,5 @@
+pan_joint_name: pan
+tilt_joint_name: tilt
+load_name: camera_base_frame
+joint_interface: EffortJointInterface
+
diff --git a/package.xml b/package.xml
index 653521b..626c394 100644
--- a/package.xml
+++ b/package.xml
@@ -55,6 +55,7 @@
   <exec_depend>iri_velodyne_lidar_description</exec_depend>
   <exec_depend>iri_bno055_imu_description</exec_depend>
   <exec_depend>iri_realsense_depth_description</exec_depend>
+  <exec_depend>iri_dynamixel_pan_tilt_description</exec_depend>
   
 
 
diff --git a/urdf/include/sensors.xacro b/urdf/include/sensors.xacro
index cff3c53..cdbe69c 100644
--- a/urdf/include/sensors.xacro
+++ b/urdf/include/sensors.xacro
@@ -4,6 +4,10 @@
   <xacro:include filename="$(find iri_velodyne_lidar_description)/urdf/velodyne_vlp16.xacro" />
   <xacro:include filename="$(find iri_realsense_depth_description)/urdf/realsense.xacro" />
   <xacro:include filename="$(find iri_bno055_imu_description)/urdf/bno055_imu.xacro" />
+  <xacro:include filename="$(find iri_dynamixel_pan_tilt_description)/urdf/pan_tilt.xacro" />
+
+  <xacro:property name="pan_tilt_xacro_conf" value="$(find iri_ana_description)/config/ana_pan_tilt_xacro.yaml"/>
+  <xacro:property name="pan_tilt_xacro_properties" value="${load_yaml(pan_tilt_xacro_conf)}"/>
 
   <xacro:macro name="sensors" params="name parent">
    
@@ -63,6 +67,44 @@
       <origin xyz="0.11928 -0.08805 0.23061" rpy="0 -1.5707 0" />
     </xacro:bno055_imu>
 
+    <link name="${pan_tilt_xacro_properties['load_name']}">
+      <visual>
+        <geometry>
+          <box size=".05 .05 .01"/>
+        </geometry>
+        <origin rpy="0 ${pi/2} 0" xyz="0 0 .025"/>
+        <material name="blue">
+          <color rgba="0 0 .8 1"/>
+        </material>
+      </visual>
+      <inertial>
+        <origin rpy="0 ${pi/2} 0" xyz="0 0 .025"/>
+        <mass value="1"/>
+        <inertia 
+          ixx="0.0001" ixy="0.0" ixz="0.0" 
+          iyy="0.0001" iyz="0.0" 
+          izz="0.0001"/>
+      </inertial>
+    </link>
+
+    <link name="camera_optical_frame"/>
+
+    <gazebo reference="${pan_tilt_xacro_properties['load_name']}">
+      <mu1>0.2</mu1>
+      <mu2>0.2</mu2>
+      <material>Gazebo/Blue</material>
+    </gazebo>
+
+    <joint name="${pan_tilt_xacro_properties['load_name']}_to_camera_optical_frame" type="fixed" >
+      <parent link="${pan_tilt_xacro_properties['load_name']}"/>
+      <child link="camera_optical_frame"/>
+      <origin xyz="0.0 0.0 0.025" rpy="${pi/2} 0 -${pi/2}"/>
+    </joint>
+
+    <xacro:pan_tilt parent="${name}_box" pan_joint_name="${pan_tilt_xacro_properties['pan_joint_name']}" tilt_joint_name="${pan_tilt_xacro_properties['tilt_joint_name']}" load_name="${pan_tilt_xacro_properties['load_name']}" joint_interface="${pan_tilt_xacro_properties['joint_interface']}" sim_config="$(find iri_ana_gazebo)/config/ana_pan_tilt_gazebo.yaml">
+      <origin xyz="0.15 0.0 0.2" rpy="0 0 0" />
+    </xacro:pan_tilt>
+
   </xacro:macro>
 
 </root>
-- 
GitLab