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

Gazebo ignition rosbot xl namespaces #40

Merged
merged 12 commits into from
Jan 30, 2024
23 changes: 19 additions & 4 deletions urdf/intel_realsense_d435.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,16 @@
name:=camera
topic:=camera
use_nominal_extrinsics:=false
namespace:=None
simulation_engine:=ignition-gazebo">

<xacro:if value="${namespace == 'None'}">
<xacro:property name="ns" value="" />
</xacro:if>
<xacro:unless value="${namespace == 'None'}">
<xacro:property name="ns" value="${namespace}/" />
</xacro:unless>

<xacro:if value="${tf_prefix == 'None'}">
<xacro:property name="prefix" value="" />
</xacro:if>
Expand Down Expand Up @@ -176,11 +184,12 @@
<!-- It is also possible to use single rgbd_camera sensor, but using separate rgb and depth camera
should be more accurate for D435 - different frames and fovs can be set -->
<gazebo reference="${prefix}${name}_link">
<sensor type="camera" name="${prefix}${name}_color">
<!-- https://github.com/IntelRealSense/realsense-ros#published-topics -->
<sensor type="camera" name="${ns}{prefix}${name}_intel_realsense_d435_color">
<always_on>true</always_on>
<update_rate>30.0</update_rate>

<topic>${topic}/color/image_raw</topic>
<topic>${ns}${topic}/color/image_raw</topic>
<visualize>false</visualize>

<ignition_frame_id>${prefix}${name}_color_optical_frame</ignition_frame_id>
Expand All @@ -194,13 +203,16 @@
<near>0.02</near>
<far>300.0</far>
</clip>
<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>

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

<topic>${topic}/depth</topic>
<topic>${ns}${topic}/depth/image_rect_raw</topic>
<visualize>false</visualize>

<ignition_frame_id>${prefix}${name}_depth_optical_frame</ignition_frame_id>
Expand All @@ -221,6 +233,9 @@
<stddev>0.005</stddev>
</noise>
</camera>
<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>
</gazebo>
</xacro:if>
Expand Down
43 changes: 36 additions & 7 deletions urdf/orbbec_astra.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -94,16 +94,40 @@

<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<gazebo reference="${prefix}${camera_name}_orbbec_astra_link">
<sensor type="rgbd_camera" name="${prefix}${camera_name}_orbbec_astra_camera">
<!-- https://github.com/orbbec/OrbbecSDK_ROS2#all-available-topics -->
<sensor type="camera" name="${ns}{prefix}${camera_name}_orbbec_astra_color">
<always_on>true</always_on>
<update_rate>20.0</update_rate>
<update_rate>30.0</update_rate>

<topic>${ns}${camera_name}/color/image_raw</topic>
<visualize>false</visualize>

<ignition_frame_id>${prefix}${camera_name}_color_optical_frame</ignition_frame_id>
<horizontal_fov>${60.0/180.0*pi}</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>

<clip>
<near>0.6</near>
<far>8.0</far>
</clip>
<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>

<topic>${ns}${camera_name}</topic>
<!-- It is not possible to split the frame of the color and the depth stream.
The frame of color stream should be ${prefix}${camera_name}_color_optical_frame -->
<ignition_frame_id>${prefix}${camera_name}_depth_optical_frame</ignition_frame_id>
<sensor type="depth_camera" name="${ns}${prefix}${camera_name}_orbbec_astra_depth">
<always_on>true</always_on>
<update_rate>10.0</update_rate>

<camera name="${prefix}camera">

<topic>${ns}${camera_name}/depth/image_raw</topic>
<visualize>false</visualize>

<ignition_frame_id>${prefix}${camera_name}_depth_optical_frame</ignition_frame_id>
<camera>
<horizontal_fov>${60.0/180.0*pi}</horizontal_fov>
<image>
<width>640</width>
Expand All @@ -114,6 +138,11 @@
<near>0.6</near>
<far>8.0</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.005</stddev>
</noise>
</camera>
<ros>
<namespace>${ns}</namespace>
Expand Down
6 changes: 3 additions & 3 deletions urdf/slamtec_rplidar_s3.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -112,10 +112,10 @@
</ray>
<always_on>1</always_on>
<visualize>false</visualize>
<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>
<ros>
<namespace>${ns}</namespace>
</ros>
</gazebo>
</xacro:if>

Expand Down
28 changes: 20 additions & 8 deletions urdf/stereolabs_zed.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,18 @@
<xacro:macro name="zed_camera"
params="parent_link xyz rpy
model:=zed
namespace:=None
tf_prefix:=None
name:=camera
topic:=camera
use_nominal_extrinsics:=false
simulation_engine:=ignition-gazebo">

<xacro:if value="${namespace == 'None'}">
<xacro:property name="ns" value="" />
</xacro:if>
<xacro:unless value="${namespace == 'None'}">
<xacro:property name="ns" value="${namespace}/" />
</xacro:unless>

<xacro:if value="${tf_prefix == 'None'}">
<xacro:property name="prefix" value="" />
</xacro:if>
Expand Down Expand Up @@ -85,10 +91,10 @@
</xacro:if>

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

Expand Down Expand Up @@ -183,11 +189,11 @@
camera
should be more accurate different frames and fovs can be set -->
<gazebo reference="${prefix}${name}_center_optical_frame">
<sensor type="camera" name="${prefix}${name}_color">
<sensor type="camera" name="${ns}${prefix}${name}_stereolabs_zed_color">
<always_on>true</always_on>
<update_rate>30.0</update_rate>

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

<ignition_frame_id>${prefix}${name}_center_optical_frame</ignition_frame_id>
Expand All @@ -203,13 +209,16 @@
<far>300.0</far>
</clip>
</camera>
<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>

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

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

<ignition_frame_id>${prefix}${name}_center_optical_frame</ignition_frame_id>
Expand All @@ -229,6 +238,9 @@
<stddev>0.03</stddev>
</noise>
</camera>
<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>
</gazebo>
</xacro:if>
Expand Down
20 changes: 13 additions & 7 deletions urdf/velodyne_puck.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,16 @@
tf_prefix:=None
topic:=scan
frame_id:=velodyne
namespace:=None
simulation_engine:=gazebo-classic">

<xacro:if value="${namespace == 'None'}">
<xacro:property name="ns" value="" />
</xacro:if>
<xacro:unless value="${namespace == 'None'}">
<xacro:property name="ns" value="${namespace}/" />
</xacro:unless>

<xacro:if value="${use_gpu}">
<xacro:property name="ray_type" value="gpu_ray" />
<xacro:property name="plugin_file_name" value="libgazebo_ros_velodyne_gpu_laser.so" />
Expand Down Expand Up @@ -64,7 +72,7 @@
<link name="${prefix}${frame_id}" />

<gazebo reference="${prefix}${frame_id}">
<sensor type="${ray_type}" name="${prefix}velodyne_puck_sensor">
<sensor type="${ray_type}" name="${ns}${prefix}velodyne_puck_sensor">
<visualize>false</visualize>
<update_rate>10.0</update_rate>

Expand Down Expand Up @@ -96,14 +104,10 @@
</ray>

<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<topic>${topic}</topic>
<topic>${ns}${topic}</topic>
<frame_id>${prefix}${frame_id}</frame_id>
<ignition_frame_id>${prefix}${frame_id}</ignition_frame_id>
<always_on>true</always_on>
<plugin filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
</xacro:if>

<xacro:if value="${simulation_engine == 'gazebo-classic'}">
Expand All @@ -117,7 +121,9 @@
<frame_name>${prefix}${frame_id}</frame_name>
</plugin>
</xacro:if>

<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>
</gazebo>
</xacro:macro>
Expand Down
Loading