Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Workspace with ZED for Simulation and Real Camera #25

Open
wants to merge 30 commits into
base: main
Choose a base branch
from
Open
Changes from 1 commit
Commits
Show all changes
30 commits
Select commit Hold shift + click to select a range
d508895
Create zed_ws.
YuZhong-Chen Dec 30, 2023
85a3fb9
Clone zed-ros2-wrapper.
YuZhong-Chen Dec 30, 2023
0c2179c
Update Dockerfile base image to ZED.
YuZhong-Chen Dec 30, 2023
6f98159
Enable GPU access within the container.
YuZhong-Chen Jan 19, 2024
ac9d5c3
Clone zed-ros2-examples.
YuZhong-Chen Dec 30, 2023
bb504a6
Install ros2 humble in Dockerfile.
YuZhong-Chen Dec 30, 2023
da913ff
Clone zed gazebo settings.
YuZhong-Chen Jan 17, 2024
8beebb4
Remove the link in ZED urdf.
YuZhong-Chen Jan 17, 2024
65790cf
Add the tag `inertial` in ZED urdf.
YuZhong-Chen Jan 17, 2024
14b8901
Update the Dockerfile to include ZED dependencies.
YuZhong-Chen Jan 19, 2024
497d322
Change the ownership of the ZED folder.
YuZhong-Chen Jan 19, 2024
718acdd
Update compose.yaml to mount devices.
YuZhong-Chen Jan 19, 2024
4edff3f
Add the Gazebo plugin for ZED.
YuZhong-Chen Jan 19, 2024
7f8de9e
Integrate the launch settings for Gazebo.
YuZhong-Chen Jan 19, 2024
cbb77e3
Adjust the parameters in the Gazebo settings.
YuZhong-Chen Jan 19, 2024
f421584
Tweak the camera distortion parameters.
YuZhong-Chen Jan 19, 2024
3567e54
Update README.md
YuZhong-Chen Jan 19, 2024
1cf5737
Add Dockerfile for Isaac Sim.
YuZhong-Chen Feb 3, 2024
c64d89d
Add the Docker Compose settings for Isaac Sim.
YuZhong-Chen Feb 3, 2024
5bc3e85
Add gitkeep files for Isaac Sim cache.
YuZhong-Chen Feb 3, 2024
8a7b136
Install ROS2 Humble in Isaac Sim container.
YuZhong-Chen Feb 3, 2024
2a09afb
Install ZED SDK in Isaac Sim container.
YuZhong-Chen Feb 3, 2024
f47dc4c
Fix permissions and handle special cases in Dockerfile.
YuZhong-Chen Feb 3, 2024
df2e5d3
Clone zed-isaac-sim.
YuZhong-Chen Feb 3, 2024
66abdb4
Alter the ownership of the mounted folders.
YuZhong-Chen Feb 3, 2024
b6365ad
Fix permissions of the Isaac Sim.
YuZhong-Chen Feb 3, 2024
db1ec09
Add an example for Isaac Sim.
YuZhong-Chen Feb 3, 2024
7a446d6
Modify the ROS2 environment variables and provide additional comments…
YuZhong-Chen Feb 3, 2024
6c82dbd
Activate the Isaac Sim feature in zed-ros2-wrapper.
YuZhong-Chen Feb 3, 2024
b30e5cb
Update README.md
YuZhong-Chen Feb 3, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
309 changes: 309 additions & 0 deletions zed_ws/src/zed-ros2-wrapper/zed_wrapper/urdf/zed_gazebo.urdf.xacro
j3soon marked this conversation as resolved.
Show resolved Hide resolved
YuZhong-Chen marked this conversation as resolved.
Show resolved Hide resolved
YuZhong-Chen marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
@@ -0,0 +1,309 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:property name="baseline" value="0.12"/>

<xacro:macro name="zed2"
params="link_prefix:=''
joint_prefix:=''">

<!-- Camera Center -->
<link name="${link_prefix}zed2_camera_center">
<inertial>
<mass value="0.16140"/>
<origin xyz="0 0 0"/>
<inertia
ixx="0.0003947" ixy="0.0" ixz="3.3365e-8"
iyy="2.417e-5" iyz="0.0"
izz="0.0003973"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://leo_erc_description/models/ZED2.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://leo_erc_description/models/ZED2.dae"/>
</geometry>
</collision>
</link>

<!-- Left Camera -->
<joint name="${joint_prefix}zed2_left_camera_joint" type="fixed">
<parent link="${link_prefix}zed2_camera_center"/>
<child link="${link_prefix}zed2_left_camera_frame"/>
<origin xyz="0 ${baseline/2} 0" rpy="0 0 0" />
</joint>

<link name="${link_prefix}zed2_left_camera_frame" />

<joint name="${joint_prefix}zed2_left_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${pi/2} 0.0 -${pi/2}"/>
<parent link="${link_prefix}zed2_left_camera_frame"/>
<child link="${link_prefix}zed2_left_camera_optical_frame"/>
</joint>

<link name="${link_prefix}zed2_left_camera_optical_frame"/>

<!-- Right Camera -->
<joint name="${joint_prefix}zed2_right_camera_joint" type="fixed">
<parent link="${link_prefix}zed2_camera_center"/>
<child link="${link_prefix}zed2_right_camera_frame"/>
<origin xyz="0 -${baseline/2} 0" rpy="0 0 0" />
</joint>

<link name="${link_prefix}zed2_right_camera_frame" />

<joint name="${joint_prefix}zed2_right_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${pi/2} 0.0 -${pi/2}"/>
<parent link="${link_prefix}zed2_right_camera_frame"/>
<child link="${link_prefix}zed2_right_camera_optical_frame"/>
</joint>

<link name="${link_prefix}zed2_right_camera_optical_frame"/>

<!-- Sensors -->
<joint name="${joint_prefix}zed2_mag_joint" type="fixed">
<parent link="${link_prefix}zed2_camera_center"/>
<child link="${link_prefix}zed2_mag_link"/>
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<link name="${link_prefix}zed2_mag_link" />

<joint name="${joint_prefix}zed2_baro_joint" type="fixed">
<parent link="${link_prefix}zed2_camera_center"/>
<child link="${link_prefix}zed2_baro_link"/>
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<link name="${link_prefix}zed2_baro_link" />

<joint name="${joint_prefix}zed2_temp_left_joint" type="fixed">
<parent link="${link_prefix}zed2_left_camera_frame"/>
<child link="${link_prefix}zed2_temp_left_link"/>
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<link name="${link_prefix}zed2_temp_left_link" />

<joint name="${joint_prefix}zed2_temp_right_joint" type="fixed">
<parent link="${link_prefix}zed2_right_camera_frame"/>
<child link="${link_prefix}zed2_temp_right_link"/>
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<link name="${link_prefix}zed2_temp_right_link" />

</xacro:macro>


<xacro:macro name="zed2_gazebo"
params="robot_ns:=''">

<xacro:property name="link_prefix" value=""/>
<xacro:if value="${robot_ns != '' and robot_ns != '/'}">
<xacro:property name="link_prefix" value="${robot_ns}/"/>
</xacro:if>

<!-- Left/Depth camera -->
<gazebo reference="${link_prefix}zed2_left_camera_frame">
<!-- Raw images (with lens distortion) -->
<sensor type="camera" name="zed2_left_raw_camera">
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<visualize>false</visualize>
<camera name="zed2_left_raw">
<horizontal_fov>1.7633</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
<distortion>
<!-- Values copied from an actual ZED2 camera -->
<k1>-0.043693598</k1>
<k2>0.0146164996</k2>
<p1>-0.006573319</p1>
<p2>-0.000216900</p2>
<k3>0.000084328</k3>
<center>0.5 0.5</center>
</distortion>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<robotNamespace>${robot_ns}</robotNamespace>
<cameraName>zed2/left_raw</cameraName>
<imageTopicName>image_raw_color</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>zed2_left_camera_optical_frame</frameName>
<distortionK1>-0.043693598</distortionK1>
<distortionK2>0.0146164996</distortionK2>
<distortionT1>-0.006573319</distortionT1>
<distortionT2>-0.000216900</distortionT2>
<distortionK3>0.000084328</distortionK3>
<CxPrime>648.5</CxPrime>
<Cx>648.5</Cx>
<Cy>366.8340148925781</Cy>
<hackBaseline>0.0</hackBaseline>
</plugin>
</sensor>

<sensor type="depth" name="zed2_left_camera">
<!-- Rectified images, Depth images, Point Clouds -->
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<visualize>false</visualize>
<camera name="zed2_left">
<horizontal_fov>1.7633</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_openni_kinect.so">
<robotNamespace>${robot_ns}</robotNamespace>
<cameraName>zed2</cameraName>
<imageTopicName>left/image_rect_color</imageTopicName>
<cameraInfoTopicName>left/camera_info</cameraInfoTopicName>
<depthImageTopicName>depth/depth_registered</depthImageTopicName>
<depthImageInfoTopicName>depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>point_cloud/cloud_registered</pointCloudTopicName>
<pointCloudCutoff>0.3</pointCloudCutoff>
<pointCloudCutoffMax>20.0</pointCloudCutoffMax>
<frameName>zed2_left_camera_optical_frame</frameName>
<baseline>0.12</baseline>
<CxPrime>658.8206787109375</CxPrime>
<Cx>658.8206787109375</Cx>
<Cy>372.25787353515625</Cy>
<hackBaseline>0.0</hackBaseline>
</plugin>
</sensor>
</gazebo>

<!-- Right camera -->
<gazebo reference="${link_prefix}zed2_right_camera_frame">
<!-- Raw images (with lens distortion) -->
<sensor type="camera" name="zed2_right_raw_camera">
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<visualize>false</visualize>
<camera name="zed2_right_raw">
<horizontal_fov>1.7633</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
<distortion>
<k1>-0.040993299</k1>
<k2>0.009593590</k2>
<p1>-0.004429849</p1>
<p2>0.000192024</p2>
<k3>-0.000320880</k3>
<center>0.5 0.5</center>
</distortion>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<robotNamespace>${robot_ns}</robotNamespace>
<cameraName>zed2/right_raw</cameraName>
<imageTopicName>image_raw_color</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>zed2_right_camera_optical_frame</frameName>
<distortionK1>-0.040993299</distortionK1>
<distortionK2>0.009593590</distortionK2>
<distortionT1>-0.004429849</distortionT1>
<distortionT2>0.000192024</distortionT2>
<distortionK3>-0.000320880</distortionK3>
<CxPrime>659.3049926757812</CxPrime>
<Cx>659.3049926757812</Cx>
<Cy>371.39849853515625</Cy>
<hackBaseline>0.12</hackBaseline>
</plugin>
</sensor>

<sensor type="camera" name="zed2_right_camera">
<!-- Rectified images -->
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<visualize>false</visualize>
<camera name="zed2_right">
<horizontal_fov>1.7633</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<robotNamespace>${robot_ns}</robotNamespace>
<cameraName>zed2/right</cameraName>
<imageTopicName>image_rect_color</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>zed2_right_camera_optical_frame</frameName>
<CxPrime>658.8206787109375</CxPrime>
<Cx>658.8206787109375</Cx>
<Cy>372.25787353515625</Cy>
<hackBaseline>0.12</hackBaseline>
</plugin>
</sensor>
</gazebo>

<!-- IMU -->
<gazebo reference="${link_prefix}zed2_left_camera_frame">
<sensor type="imu" name="zed2_imu_sensor">
<update_rate>100</update_rate>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<robotNamespace>${robot_ns}</robotNamespace>
<topicName>zed2/imu/data</topicName>
<frameName>zed2_imu_link</frameName>
<updateRateHZ>100.0</updateRateHZ>
<gaussianNoise>0.01</gaussianNoise>
<initialOrientationAsReference>false</initialOrientationAsReference>
<!-- IMU frame offset copied from an actual ZED2 camera -->
<xyzOffset>-0.002 -0.023 -0.002</xyzOffset>
<rpyOffset>0.0014025 -0.0000012 -0.0016915</rpyOffset>
</plugin>
</sensor>
</gazebo>

</xacro:macro>

</robot>