Skip to content

Commit

Permalink
updates?
Browse files Browse the repository at this point in the history
  • Loading branch information
Michael Equi committed Mar 14, 2019
1 parent 1f81e87 commit 52868d2
Show file tree
Hide file tree
Showing 2 changed files with 366 additions and 0 deletions.
183 changes: 183 additions & 0 deletions urdf/_d415.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,183 @@
<?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 410 camera, in it's
aluminum peripherial evaluation case.
-->

<robot name="sensor_d415" xmlns:xacro="http://www.ros.org/wiki/xacro">
<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="d415_cam_depth_to_left_ir_offset" value="0.0"/>
<xacro:property name="d415_cam_depth_to_right_ir_offset" value="-0.050"/>
<xacro:property name="d415_cam_depth_to_color_offset" value="0.015"/>

<!-- The following values model the aluminum peripherial case for the
d415 camera, with the camera joint represented by the actual
peripherial camera tripod mount -->
<xacro:property name="d415_cam_width" value="0.090"/>
<xacro:property name="d415_cam_height" value="0.03"/>
<xacro:property name="d415_cam_depth" value="0.02505"/>
<xacro:property name="d415_cam_mount_from_center_offset" value="0.0149"/>

<!-- The following offset is relative the the physical d415 camera peripherial
camera tripod mount -->
<xacro:property name="d415_cam_depth_px" value="${d415_cam_mount_from_center_offset}"/>
<xacro:property name="d415_cam_depth_py" value="0.0175"/>
<xacro:property name="d415_cam_depth_pz" value="${d415_cam_height/2}"/>

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

<xacro:macro name="sensor_d415" params="parent camera_name *origin">

<!-- 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="0.007 0 ${d415_cam_height/2+0.0015}" rpy="0 0 ${M_PI/2}"/>
<geometry>
<!--<box size="${d415_cam_width} ${d415_cam_height} ${d415_cam_depth}"/>-->
<mesh filename="package://realsense2_description/meshes/d415.dae" />
</geometry>
<material name="aluminum"/>
</visual>
<collision>
<origin xyz="0.0 0.0 ${d415_cam_height/2}" rpy="0 0 0"/>
<geometry>
<box size="${d415_cam_depth} ${d415_cam_width} ${d415_cam_height}"/>
</geometry>
</collision>
<inertial>
<!-- The following are not reliable values, and should not be used for modeling -->
<mass value="0.072" />
<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="${d415_cam_depth_px} ${d415_cam_depth_py} ${d415_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 ${d415_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 ${d415_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 ${d415_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"/>

<!-- D415 3D Depth Camera -->
<gazebo reference="camera_depth_frame">
<sensor name="realsense_d415" type="depth">
<always_on>1</always_on>
<visualize>1</visualize>
<camera name='${camera_name}'>
<horizontal_fov>1.1065</horizontal_fov>
<image> <!-- Values can be changed in physical version -->
<width>1280</width>
<height>720</height>
<format>B8G8R8</format>
</image>
<depth_camera>
<output>depths</output>
</depth_camera>
<clip>
<near>0.1</near>
<far>200</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_link_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>${camera_name}_ir</cameraName>
<imageTopicName>/${camera_name}/color/image_raw</imageTopicName>
<cameraInfoTopicName>/${camera_name}/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/${camera_name}/depth/image_raw</depthImageTopicName>
<depthImageInfoTopicName>/${camera_name}/depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>/${camera_name}/depth/color/points</pointCloudTopicName>
<frameName>/camera_depth_optical_frame</frameName>
<pointCloudCutoff>0.16</pointCloudCutoff>
<pointCloudCutoffmax>8</pointCloudCutoffmax>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0.0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>

</xacro:macro>
</robot>
183 changes: 183 additions & 0 deletions urdf/_d435.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,183 @@
<?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.
-->

<robot name="sensor_d435" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="sensor_d435" params="parent camera_name *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_description/meshes/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.072" />
<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"/>

<!-- D435 3D Depth Camera -->
<gazebo reference="camera_depth_frame">
<sensor name="realsense_d435" type="depth">
<always_on>1</always_on>
<visualize>1</visualize>
<camera name='${camera_name}'>
<horizontal_fov>1.487</horizontal_fov>
<image> <!-- Values can be changed in physical version -->
<width>848</width>
<height>480</height>
<format>B8G8R8</format>
</image>
<depth_camera>
<output>depths</output>
</depth_camera>
<clip>
<near>0.1</near>
<far>200</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_link_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>${camera_name}_ir</cameraName>
<imageTopicName>/${camera_name}/color/image_raw</imageTopicName>
<cameraInfoTopicName>/${camera_name}/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/${camera_name}/depth/image_raw</depthImageTopicName>
<depthImageInfoTopicName>/${camera_name}/depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>/${camera_name}/depth/color/points</pointCloudTopicName>
<frameName>/camera_depth_optical_frame</frameName>
<pointCloudCutoff>0.11</pointCloudCutoff>
<pointCloudCutoffmax>8</pointCloudCutoffmax>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0.0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>

</xacro:macro>
</robot>

0 comments on commit 52868d2

Please sign in to comment.