Skip to content

Commit

Permalink
Merge pull request #54 from deebuls/intel_d435_xacro
Browse files Browse the repository at this point in the history
[URDF] Adding intel D435 urdf and updating urdf of youbot 2
  • Loading branch information
deebuls committed Feb 22, 2019
2 parents 68c2d1a + b3cd26b commit bb7a0e1
Show file tree
Hide file tree
Showing 3 changed files with 866 additions and 2 deletions.
731 changes: 731 additions & 0 deletions mir_common/mir_description/meshes/sensor_mounts/d435.dae

Large diffs are not rendered by default.

132 changes: 132 additions & 0 deletions mir_common/mir_description/urdf/sensors/d435.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
<?xml version="1.0"?>

<!--
License: Apache 2.0. See LICENSE file in root directory.
Copyright(c) 2017 Intel Corporation. All Rights Reserved
This is the URDF model for the Intel RealSense 430 camera, in it's
aluminum peripherial evaluation case.
-->

<root xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="sensor_d435" params="name parent *origin">
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- The following values are approximate, and the camera node
publishing TF values with actual calibrated camera extrinsic values -->
<xacro:property name="d435_cam_depth_to_left_ir_offset" value="0.0"/>
<xacro:property name="d435_cam_depth_to_right_ir_offset" value="-0.050"/>
<xacro:property name="d435_cam_depth_to_color_offset" value="0.015"/>

<!-- The following values model the aluminum peripherial case for the
D435 camera, with the camera joint represented by the actual
peripherial camera tripod mount -->
<xacro:property name="d435_cam_width" value="0.090"/>
<xacro:property name="d435_cam_height" value="0.025"/>
<xacro:property name="d435_cam_depth" value="0.02505"/>
<xacro:property name="d435_cam_mount_from_center_offset" value="0.0149"/>

<!-- The following offset is relative the the physical D435 camera peripherial
camera tripod mount -->
<xacro:property name="d435_cam_depth_px" value="${d435_cam_mount_from_center_offset}"/>
<xacro:property name="d435_cam_depth_py" value="0.0175"/>
<xacro:property name="d435_cam_depth_pz" value="${d435_cam_height/2}"/>

<material name="aluminum">
<color rgba="0.5 0.5 0.5 1"/>
</material>


<!-- camera body, with origin at bottom screw mount -->
<joint name="camera_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="camera_link" />
</joint>

<link name="camera_link">
<visual>
<origin xyz="${d435_cam_mount_from_center_offset} 0.0 ${d435_cam_height/2}" rpy="${M_PI/2} 0 ${M_PI/2}"/>
<geometry>
<!-- <box size="${d435_cam_width} ${d435_cam_height} ${d435_cam_depth}"/> -->
<!-- mesh filename="package://realsense2_camera/meshes/d435.dae" / -->
<mesh filename="package://mcr_description/meshes/sensors/d435.dae" />
<!--<mesh filename="package://realsense2_camera/meshes/d435/d435.dae" />-->
</geometry>
<material name="aluminum"/>
</visual>
<collision>
<origin xyz="0.0 0.0 ${d435_cam_height/2}" rpy="0 0 0"/>
<geometry>
<box size="${d435_cam_depth} ${d435_cam_width} ${d435_cam_height}"/>
</geometry>
</collision>
<inertial>
<!-- The following are not reliable values, and should not be used for modeling -->
<mass value="0.564" />
<origin xyz="0 0 0" />
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257" />
</inertial>
</link>

<!-- camera depth joints and links -->
<joint name="camera_depth_joint" type="fixed">
<origin xyz="${d435_cam_depth_px} ${d435_cam_depth_py} ${d435_cam_depth_pz}" rpy="0 0 0"/>
<parent link="camera_link"/>
<child link="camera_depth_frame" />
</joint>
<link name="camera_depth_frame"/>

<joint name="camera_depth_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_depth_frame" />
<child link="camera_depth_optical_frame" />
</joint>
<link name="camera_depth_optical_frame"/>

<!-- camera left IR joints and links -->
<joint name="camera_left_ir_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_left_ir_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_left_ir_frame" />
</joint>
<link name="camera_left_ir_frame"/>

<joint name="camera_left_ir_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_left_ir_frame" />
<child link="camera_left_ir_optical_frame" />
</joint>
<link name="camera_left_ir_optical_frame"/>

<!-- camera right IR joints and links -->
<joint name="camera_right_ir_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_right_ir_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_right_ir_frame" />
</joint>
<link name="camera_right_ir_frame"/>

<joint name="camera_right_ir_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_right_ir_frame" />
<child link="camera_right_ir_optical_frame" />
</joint>
<link name="camera_right_ir_optical_frame"/>

<!-- camera color joints and links -->
<joint name="camera_color_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_color_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_color_frame" />
</joint>
<link name="camera_color_frame"/>

<joint name="camera_color_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_color_frame" />
<child link="camera_color_optical_frame" />
</joint>
<link name="camera_color_optical_frame"/>
</xacro:macro>
</root>
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<xacro:include filename="$(find mir_description)/urdf/sensor_mounts/intel_f200_camera_mount.urdf.xacro"/>
<xacro:include filename="$(find mcr_description)/urdf/sensors/intel_realsense_f200_camera.urdf.xacro"/>
<xacro:include filename="$(find mir_description)/urdf/sensors/asus_xtion_camera.urdf.xacro"/>
<xacro:include filename="$(find mir_description)/urdf/sensors/d435.urdf.xacro"/>
<xacro:include filename="$(find mir_description)/urdf/sensor_mounts/asus_xtion_camera_mount.urdf.xacro"/>

<!-- Now we can start using the macros included above to define the actual youbot -->
Expand Down Expand Up @@ -64,11 +65,11 @@
<!-- xacro:intel_realsense_f200_camera name="arm_cam3d" parent="camera_mount_link">
<origin xyz="-0.05 -0.01 0.03" rpy="0.0 -${M_PI/2 - 0.03} 0.0" />
</xacro:intel_realsense_f200_camera -->
<xacro:asus_xtion_camera name="arm_cam3d" parent="camera_mount_link">
<xacro:sensor_d435 name="arm_cam3d" parent="camera_mount_link">
<!--origin xyz="-0.01 -0.012 0.05" rpy="0 ${M_PI/2 - 0.25} 0.00" /-->
<!--origin xyz="0.016 0 0.01" rpy="0 ${M_PI/2 - 0} -0.09" /> -->
<origin xyz="0.010 -0.022 0.017" rpy="0 ${M_PI/2 - 0.18} -${M_PI/2}" />
<!--origin xyz="0.023 -0.015 0.03" rpy="0 0 0" /-->
</xacro:asus_xtion_camera>
</xacro:sensor_d435>

</robot>

0 comments on commit bb7a0e1

Please sign in to comment.