Skip to content

Commit

Permalink
Merge pull request #31 from husarion/add-zed-urdf
Browse files Browse the repository at this point in the history
Add zed urdf
  • Loading branch information
rafal-gorecki authored Nov 8, 2023
2 parents 5f94c33 + d95c65c commit 3fefa6e
Show file tree
Hide file tree
Showing 9 changed files with 250 additions and 20 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
.vscode
Binary file added meshes/zed.stl
Binary file not shown.
Binary file added meshes/zed2.stl
Binary file not shown.
Binary file added meshes/zed2i.stl
Binary file not shown.
Binary file added meshes/zedm.stl
Binary file not shown.
Binary file added meshes/zedx.stl
Binary file not shown.
Binary file added meshes/zedxm.stl
Binary file not shown.
40 changes: 20 additions & 20 deletions urdf/intel_realsense_d435.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
# limitations under the License.
-->

<robot xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="intel_camera" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="intel_realsense_d435"
params="parent_link xyz rpy
name:=camera
Expand Down Expand Up @@ -195,26 +195,26 @@
<topic>${topic}/depth</topic>
<visualize>false</visualize>

<!-- Pointcloud is published in internal gazebo frame name, and there seem to be no
way to change it, interestingly depth image is published correctly in the ignition_frame_id -->
<ignition_frame_id>${name}_depth_frame</ignition_frame_id>

<horizontal_fov>${87.0/180.0*pi}</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
</image>
<clip>
<near>0.28</near>
<far>8.0</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.005</stddev>
</noise>
<ignition_frame_id>${name}_depth_optical_frame</ignition_frame_id>
<camera>
<horizontal_fov>${87.0/180.0*pi}</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R_FLOAT32</format>
</image>
<clip>
<near>0.28</near>
<far>8.0</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.005</stddev>
</noise>
</camera>
</sensor>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>
</robot>
229 changes: 229 additions & 0 deletions urdf/stereolabs_zed.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,229 @@
<?xml version="1.0"?>

<!--
// Copyright 2022 Stereolabs
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
-->

<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />

<xacro:macro name="zed_camera"
params="parent_link xyz rpy
model:=zed
name:=camera
topic:=camera
use_nominal_extrinsics:=false
simulation_engine:=ignition-gazebo">

<xacro:if value="${model == 'zed'}">
<xacro:property name="baseline" value="0.12" />
<xacro:property name="height" value="0.03" />
<xacro:property name="bottom_slope" value="0.05" />
<xacro:property name="screw_offset_x" value="0.0" />
<xacro:property name="screw_offset_z" value="0.0" />
<xacro:property name="optical_offset_x" value="-0.01" />
</xacro:if>
<xacro:if value="${model == 'zedm'}">
<xacro:property name="baseline" value="0.06" />
<xacro:property name="height" value="0.0265" />
<xacro:property name="bottom_slope" value="0.0" />
<xacro:property name="screw_offset_x" value="0.0" />
<xacro:property name="screw_offset_z" value="0.0" />
<xacro:property name="optical_offset_x" value="0.0" />
</xacro:if>
<xacro:if value="${model == 'zed2'}">
<xacro:property name="baseline" value="0.12" />
<xacro:property name="height" value="0.03" />
<xacro:property name="bottom_slope" value="0.05" />
<xacro:property name="screw_offset_x" value="0.0" />
<xacro:property name="screw_offset_z" value="0.0" />
<xacro:property name="optical_offset_x" value="-0.01" />
</xacro:if>
<xacro:if value="${model == 'zed2i'}">
<xacro:property name="baseline" value="0.12" />
<xacro:property name="height" value="0.03" />
<xacro:property name="bottom_slope" value="0.0" />
<xacro:property name="screw_offset_x" value="-0.01" />
<xacro:property name="screw_offset_z" value="0.0" />
<xacro:property name="optical_offset_x" value="-0.01" />
</xacro:if>
<xacro:if value="${model == 'zedx'}">
<xacro:property name="baseline" value="0.12" />
<xacro:property name="height" value="0.032" />
<xacro:property name="bottom_slope" value="0.0" />
<xacro:property name="screw_offset_x" value="0.0" />
<xacro:property name="screw_offset_z" value="-0.016" />
<xacro:property name="optical_offset_x" value="-0.01" />
</xacro:if>
<xacro:if value="${model == 'zedxm'}">
<xacro:property name="baseline" value="0.05" />
<xacro:property name="height" value="0.032" />
<xacro:property name="bottom_slope" value="0.0" />
<xacro:property name="screw_offset_x" value="0.0" />
<xacro:property name="screw_offset_z" value="-0.016" />
<xacro:property name="optical_offset_x" value="-0.01" />
</xacro:if>

<!-- Camera mounting point (the threaded screw hole in the bottom) -->
<link name="${name}_link" />
<joint name="${name}_base_joint" type="fixed">
<parent link="${parent_link}" />
<child link="${name}_link" />
<origin xyz="${xyz}" rpy="${rpy}" />
</joint>

<!-- Camera Center -->
<link name="${name}_camera_center">
<visual>
<origin xyz="${screw_offset_x} 0 ${screw_offset_z}" rpy="0 0 0" />
<geometry>
<mesh filename="file://$(find ros_components_description)/meshes/${model}.stl" />
</geometry>
<material name="mat">
<color rgba="0.25 0.25 0.25 0.99" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="file://$(find ros_components_description)/meshes/${model}.stl" />
</geometry>
</collision>
</link>
<joint name="${name}_camera_center_joint" type="fixed">
<parent link="${name}_link" />
<child link="${name}_camera_center" />
<origin xyz="0 0 ${height/2}" rpy="0 ${bottom_slope} 0" />
</joint>

<!-- Artificially Created Camera Center -->
<link name="${name}_center_optical_frame" />
<joint name="${name}_center_joint" type="fixed">
<parent link="${name}_camera_center" />
<child link="${name}_center_optical_frame" />
<origin xyz="0.01 0 0" rpy="0 0 0" />
</joint>

<!-- Left Camera -->
<link name="${name}_left_camera_frame" />
<joint name="${name}_left_camera_joint" type="fixed">
<parent link="${name}_camera_center" />
<child link="${name}_left_camera_frame" />
<origin xyz="${optical_offset_x} ${baseline/2} 0" rpy="0 0 0" />
</joint>

<link name="${name}_left_camera_optical_frame" />
<joint name="${name}_left_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0.0 -${M_PI/2}" />
<parent link="${name}_left_camera_frame" />
<child link="${name}_left_camera_optical_frame" />
</joint>

<!-- Right Camera -->
<link name="${name}_right_camera_frame" />
<joint name="${name}_right_camera_joint" type="fixed">
<parent link="${name}_camera_center" />
<child link="${name}_right_camera_frame" />
<origin xyz="${optical_offset_x} -${baseline/2} 0" rpy="0 0 0" />
</joint>

<link name="${name}_right_camera_optical_frame" />
<joint name="${name}_right_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${M_PI/2} 0.0 -${M_PI/2}" />
<parent link="${name}_right_camera_frame" />
<child link="${name}_right_camera_optical_frame" />
</joint>


<!-- ZED2 Sensors -->
<xacro:if value="${model == 'zed2'}">
<link name="${name}_mag_link" />
<joint name="${name}_mag_joint" type="fixed">
<parent link="${name}_camera_center" />
<child link="${name}_mag_link" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<link name="${name}_baro_link" />
<joint name="${name}_baro_joint" type="fixed">
<parent link="${name}_camera_center" />
<child link="${name}_baro_link" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<link name="${name}_temp_left_link" />
<joint name="${name}_temp_left_joint" type="fixed">
<parent link="${name}_left_camera_frame" />
<child link="${name}_temp_left_link" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
</xacro:if>

<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<!-- It is also possible to use single rgbd_camera sensor, but using separate rgb and depth
camera
should be more accurate different frames and fovs can be set -->
<gazebo reference="${name}_center_optical_frame">
<sensor type="camera" name="${name}_color">
<always_on>true</always_on>
<update_rate>30.0</update_rate>

<topic>${model}/zed_node/rgb/image_rect_color</topic>
<visualize>false</visualize>

<ignition_frame_id>${name}_center_optical_frame</ignition_frame_id>
<camera>
<horizontal_fov>${110.0/180.0*pi}</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300.0</far>
</clip>
</camera>
</sensor>

<sensor type="depth_camera" name="${name}_depth">
<always_on>true</always_on>
<update_rate>30.0</update_rate>

<topic>${model}/zed_node/depth</topic>
<visualize>false</visualize>

<ignition_frame_id>${name}_center_optical_frame</ignition_frame_id>
<camera>
<horizontal_fov>${110.0/180.0*pi}</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
<format>R_FLOAT32</format>
</image>
<clip>
<near>0.3</near>
<far>20.0</far>
</clip>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>0.03</stddev>
</noise>
</camera>
</sensor>
</gazebo>
</xacro:if>

</xacro:macro>
</robot>

0 comments on commit 3fefa6e

Please sign in to comment.