Skip to content

Add RGBD, RGB and RGB triggered options #2

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

Merged
merged 3 commits into from
Oct 14, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
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
118 changes: 41 additions & 77 deletions urdf/_d405.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -1,98 +1,62 @@
<?xml version="1.0"?>
<robot name="gazebo_d405" xmlns:xacro="http://www.ros.org/wiki/xacro" xmlns:ignition="http://gazebosim.org/schema">

<!--
Gazebo plugins can only be included once so this xacro assumes that a parent will include and configure them.
This xacro requires Gazebo plugin:
- ignition::gazebo::systems::Sensors
to publish simulated RGBD camera data
<xacro:include filename="$(find realsense2_gz_description)/urdf/rgb_camera.gazebo.xacro" />
<xacro:include filename="$(find realsense2_gz_description)/urdf/rgbd_camera.gazebo.xacro" />

For example:
<gazebo>
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
</gazebo>
<!-- Xacro args
name: should match the name value passed to realsense2_description sensor xacro
type: valid values [rgb or rgbd]. Sensor type you would like to simulate
fps: the target frame rate of the camera images
gz_topic_name: the topic name the image and camera_info are published to Gazebo topics
image_width: See Realsense documentation for what the physical sensor supports
image_height: See Realsense documentation for what the physical sensor supports
trigger: valid values [true, false]. Only supported with 'type=rgb' and will only publish a single image when triggered on Gazebo topic '${name}/trigger'
example command line trigger
ign topic -t "/name/trigger" -m Boolean -p "data: true" -n 1
-->
<xacro:macro name="gazebo_d405" params="
name:=camera
type:=rgbd
fps:=15
gz_topic_name:=camera
image_width:=1280
image_height:=720">
image_height:=720
triggered:=false">

<!-- Realsense D405 RGB properties
Assumptions:
Parent system (URDF or sdf) will start the Gazebo Sensors plugin. See notes in the camera.gazebo.xacros.
Simulated RGB and Depth sensors are in the same location as the RGB sensor of the physical camera.
Simulated RGB and Depth sensors and have the same FOV as the RGB physical sensor.
Note: physical hardware publishes pointcloud in `camera_depth_optical_frame` where this sensor will use
the referenced camera color_frame. -->
<xacro:property name="realsense_h_fov" value="${69 * pi/180}" />
<xacro:property name="realsense_v_fov" value="${42 * pi/180}" />
<xacro:property name="fx" value="${image_width * 0.5 / tan(realsense_h_fov * 0.5)}" />
<xacro:property name="fy" value="${image_height * 0.5 / tan(realsense_v_fov * 0.5)}" />
<xacro:property name="cx" value="${image_width * 0.5}" />
<xacro:property name="cy" value="${image_height * 0.5}" />
<xacro:property name="realsense_h_fov" value="${87 * pi/180}" />
<xacro:property name="realsense_v_fov" value="${58 * pi/180}" />
<xacro:property name="min_depth" value="0.07" />
<xacro:property name="max_depth" value="0.5" />

<gazebo reference="${name}_color_frame">
<sensor name="${name}" type="rgbd_camera">
<camera>
<horizontal_fov>${realsense_h_fov}</horizontal_fov>
<image>
<width>${image_width}</width>
<height>${image_height}</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.028</near>
<far>5</far>
</clip>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
<lens>
<intrinsics>
<fx>${fx}</fx>
<fy>${fy}</fy>
<cx>${cx}</cx>
<cy>${cy}</cy>
<s>0</s>
</intrinsics>
<projection>
<p_fx>${fx}</p_fx>
<p_fy>${fy}</p_fy>
<p_cx>${cx}</p_cx>
<p_cy>${cy}</p_cy>
<tx>0</tx>
<ty>0</ty>
</projection>
</lens>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.00</stddev>
</noise>
<depth_camera>
<clip>
<near>0.028</near>
<far>5</far>
</clip>
</depth_camera>
<optical_frame_id>${name}_color_optical_frame</optical_frame_id>
</camera>
<ignition_frame_id>${name}_color_frame</ignition_frame_id>
<always_on>1</always_on>
<update_rate>${fps}</update_rate>
<visualize>false</visualize>
<topic>${gz_topic_name}</topic>
<enable_metrics>false</enable_metrics>
</sensor>
</gazebo>
<xacro:if value="${type == 'rgbd'}">
<xacro:gazebo_rgbd name="${name}"
fps="${fps}"
gz_topic_name="${gz_topic_name}"
image_width="${image_width}"
image_height="${image_height}"
h_fov="${realsense_h_fov}"
v_fov="${realsense_v_fov}"
min_depth="${min_depth}"
max_depth="${max_depth}"/>
</xacro:if>
<xacro:if value="${type == 'rgb'}">
<xacro:gazebo_rgb name="${name}"
fps="${fps}"
gz_topic_name="${gz_topic_name}"
image_width="${image_width}"
image_height="${image_height}"
h_fov="${realsense_h_fov}"
v_fov="${realsense_v_fov}"
triggered="${triggered}"/>
</xacro:if>

</xacro:macro>
</robot>
114 changes: 39 additions & 75 deletions urdf/_d415.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -1,98 +1,62 @@
<?xml version="1.0"?>
<robot name="gazebo_d415" xmlns:xacro="http://www.ros.org/wiki/xacro" xmlns:ignition="http://gazebosim.org/schema">

<!--
Gazebo plugins can only be included once so this xacro assumes that a parent will include and configure them.
This xacro requires Gazebo plugin:
- ignition::gazebo::systems::Sensors
to publish simulated RGBD camera data
<xacro:include filename="$(find realsense2_gz_description)/urdf/rgb_camera.gazebo.xacro" />
<xacro:include filename="$(find realsense2_gz_description)/urdf/rgbd_camera.gazebo.xacro" />

For example:
<gazebo>
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
</gazebo>
<!-- Xacro args
name: should match the name value passed to realsense2_description sensor xacro
type: valid values [rgb or rgbd]. Sensor type you would like to simulate
fps: the target frame rate of the camera images
gz_topic_name: the topic name the image and camera_info are published to Gazebo topics
image_width: See Realsense documentation for what the physical sensor supports
image_height: See Realsense documentation for what the physical sensor supports
trigger: valid values [true, false]. Only supported with 'type=rgb' and will only publish a single image when triggered on Gazebo topic '${name}/trigger'
example command line trigger
ign topic -t "/name/trigger" -m Boolean -p "data: true" -n 1
-->
<xacro:macro name="gazebo_d415" params="
name:=camera
type:=rgbd
fps:=15
gz_topic_name:=camera
image_width:=1280
image_height:=720">
image_height:=720
triggered:=false">

<!-- Realsense D415 RGB properties
Assumptions:
Parent system (URDF or sdf) will start the Gazebo Sensors plugin. See notes in the camera.gazebo.xacros.
Simulated RGB and Depth sensors are in the same location as the RGB sensor of the physical camera.
Simulated RGB and Depth sensors and have the same FOV as the RGB physical sensor.
Note: physical hardware publishes pointcloud in `camera_depth_optical_frame` where this sensor will use
the referenced camera color_frame. -->
<xacro:property name="realsense_h_fov" value="${69 * pi/180}" />
<xacro:property name="realsense_v_fov" value="${42 * pi/180}" />
<xacro:property name="fx" value="${image_width * 0.5 / tan(realsense_h_fov * 0.5)}" />
<xacro:property name="fy" value="${image_height * 0.5 / tan(realsense_v_fov * 0.5)}" />
<xacro:property name="cx" value="${image_width * 0.5}" />
<xacro:property name="cy" value="${image_height * 0.5}" />
<xacro:property name="min_depth" value="0.45" />
<xacro:property name="max_depth" value="3.0" />

<gazebo reference="${name}_color_frame">
<sensor name="${name}" type="rgbd_camera">
<camera>
<horizontal_fov>${realsense_h_fov}</horizontal_fov>
<image>
<width>${image_width}</width>
<height>${image_height}</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.45</near>
<far>5</far>
</clip>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
<lens>
<intrinsics>
<fx>${fx}</fx>
<fy>${fy}</fy>
<cx>${cx}</cx>
<cy>${cy}</cy>
<s>0</s>
</intrinsics>
<projection>
<p_fx>${fx}</p_fx>
<p_fy>${fy}</p_fy>
<p_cx>${cx}</p_cx>
<p_cy>${cy}</p_cy>
<tx>0</tx>
<ty>0</ty>
</projection>
</lens>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.00</stddev>
</noise>
<depth_camera>
<clip>
<near>0.45</near>
<far>5</far>
</clip>
</depth_camera>
<optical_frame_id>${name}_color_optical_frame</optical_frame_id>
</camera>
<ignition_frame_id>${name}_color_frame</ignition_frame_id>
<always_on>1</always_on>
<update_rate>${fps}</update_rate>
<visualize>false</visualize>
<topic>${gz_topic_name}</topic>
<enable_metrics>false</enable_metrics>
</sensor>
</gazebo>
<xacro:if value="${type == 'rgbd'}">
<xacro:gazebo_rgbd name="${name}"
fps="${fps}"
gz_topic_name="${gz_topic_name}"
image_width="${image_width}"
image_height="${image_height}"
h_fov="${realsense_h_fov}"
v_fov="${realsense_v_fov}"
min_depth="${min_depth}"
max_depth="${max_depth}"/>
</xacro:if>
<xacro:if value="${type == 'rgb'}">
<xacro:gazebo_rgb name="${name}"
fps="${fps}"
gz_topic_name="${gz_topic_name}"
image_width="${image_width}"
image_height="${image_height}"
h_fov="${realsense_h_fov}"
v_fov="${realsense_v_fov}"
triggered="${triggered}"/>
</xacro:if>

</xacro:macro>
</robot>
Loading
Loading