Skip to content

Commit

Permalink
Merge pull request #45 from husarion/suggestions
Browse files Browse the repository at this point in the history
Suggestions
  • Loading branch information
delihus authored May 10, 2024
2 parents 0589e91 + 46c887f commit 20e6ae3
Show file tree
Hide file tree
Showing 10 changed files with 209 additions and 258 deletions.
5 changes: 1 addition & 4 deletions .github/workflows/colcon_test_build.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,10 @@ jobs:
colcon-test-build-ubuntu-22-04:
strategy:
matrix:
build-type: [ignition-gazebo, gazebo-classic]
ros-distro: [humble]
env:
GAZEBO_VERSION: ${{ matrix.build-type }}
runs-on: ubuntu-22.04

name: ${{ matrix.ros-distro }}
name: Build ${{ matrix.ros-distro }}
steps:
- uses: ros-tooling/[email protected]
with:
Expand Down
21 changes: 5 additions & 16 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,6 @@ git clone https://github.com/husarion/ros_components_description.git src/ros_com
# in case the package will be used within simulation
export HUSARION_ROS_BUILD_TYPE=simulation

# to specify which simulation engine will be used
# for gazebo classic
export SIMULATION_ENGINE=gazebo-classic
# for ignition gazebo
export SIMULATION_ENGINE=ignition-gazebo

rosdep update --rosdistro $ROS_DISTRO
rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y
colcon build
Expand All @@ -36,22 +30,17 @@ To include the sensor, use the following code:
<xacro:lidar.slamtec_rplidar_s1
parent_link="cover_link"
xyz="0.0 0.0 0.0"
rpy="0.0 0.0 0.0"
use_gpu="true"
simulation_engine="gazebo-classic" />
rpy="0.0 0.0 0.0" />
```

A list of parameters can be found here:

- `parent_link` [*string*, default: **None**] parent link to which sensor should be attached.
- `xyz` [*float list*, default: **None**] 3 float values defining translation between base of a sensor and parent link. Values in **m**.
- `rpy` [*float list*, default: **None**] 3 float values define rotation between parent link and base of a sensor. Values in **rad**.
- `tf_prefix` [*string*, optional] tf prefix applied before all links created by sensor. If defined, applies `<tf_prefix>_<sensor_name>`. If not defined, leaves `<sensor_name>` intact. Applies also to `frame_id` parameter.
- `topic` [*string*, default: **same as manufacturer's default**] name of topic at which simulated sensor will publish data.
- `frame_id` [*string*, default: **same as manufacturer's default**] name of final tf to which sensor will be attached. Should match one from message published by sensor.
- `use_gpu` [*bool*, default: **false**] enable GPU acceleration for sensor. Available only if sensor can be accelerated.
- `simulation_engine` [*string*, default: **gazebo-classic**] selected for which simulation engine plugins should be loaded. Currently the only supported:
- **gazebo-classic** used to select [Gazebo Classic](https://classic.gazebosim.org/).
- **ignition-gazebo** used to select [Ignition Gazebo](https://gazebosim.org/home).
- `namespace` [*string*, default: **None**] global namespace common to the entire robot.
- `device_namespace` [*string*, default: **None**] local namespace allowing to distinguish two identical devices from each other.

- `model` [*string*, default: **None**] model argument that appears when you want to load the appropriate model from a given manufacturer.

Some sensors can define their specific parameters. Refer to their definition for more info.
25 changes: 5 additions & 20 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,26 +21,11 @@
<depend>urdf</depend>
<depend>xacro</depend>

<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation) and ($SIMULATION_ENGINE == gazebo-classic)">
gazebo_plugins
</depend>

<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation) and ($SIMULATION_ENGINE == ignition-gazebo)">
ros_gz_sim
</depend>

<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation) and ($SIMULATION_ENGINE == ignition-gazebo)">
ros_gz_bridge
</depend>

<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation) and ($SIMULATION_ENGINE == ignition-gazebo)">
launch
</depend>

<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation) and ($SIMULATION_ENGINE == ignition-gazebo)">
nav2_common
</depend>

<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation)">ros_gz_sim</depend>
<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation)">ros_gz_bridge</depend>
<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation)">launch</depend>
<depend condition="($HUSARION_ROS_BUILD_TYPE == simulation)">nav2_common</depend>

<test_depend>ament_index_python</test_depend>
<test_depend>ament_python_pytest</test_depend>
<test_depend>python-yaml</test_depend>
Expand Down
2 changes: 0 additions & 2 deletions test/component.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,6 @@

<xacro:husarion_components.create_components
components_config_path="${components_config_path_property}"
use_gpu="True"
simulation_engine="ignition-gazebo"
namespace="None"
/>
</xacro:unless>
Expand Down
194 changes: 91 additions & 103 deletions urdf/intel_realsense_d435.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,9 @@
<robot name="intel_realsense_d435" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="intel_realsense_d435"
params="parent_link xyz rpy
tf_prefix:=None
name:=camera
topic:=camera
use_nominal_extrinsics:=false
namespace:=None
simulation_engine:=ignition-gazebo">
device_namespace:=camera">

<xacro:if value="${namespace == 'None'}">
<xacro:property name="ns" value="" />
Expand All @@ -34,13 +31,6 @@
<xacro:property name="ns" value="${namespace}/" />
</xacro:unless>

<xacro:if value="${tf_prefix == 'None'}">
<xacro:property name="prefix" value="" />
</xacro:if>
<xacro:unless value="${tf_prefix == 'None'}">
<xacro:property name="prefix" value="${tf_prefix}_" />
</xacro:unless>

<!-- 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_infra1_offset" value="0.0" />
Expand Down Expand Up @@ -70,22 +60,22 @@
<xacro:property name="d435_cam_depth_pz" value="${d435_cam_height/2}" />

<!-- camera body, with origin at bottom screw mount -->
<joint name="${parent_link.rstrip('_link')}_to_${prefix}${name}_bottom_screw_joint" type="fixed">
<joint name="${parent_link.rstrip('_link')}_to_${device_namespace}_bottom_screw_joint" type="fixed">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent_link}" />
<child link="${prefix}${name}_bottom_screw_frame" />
<child link="${device_namespace}_bottom_screw_frame" />
</joint>

<link name="${prefix}${name}_bottom_screw_frame" />
<link name="${device_namespace}_bottom_screw_frame" />

<joint name="${prefix}${name}_bottom_screw_to_${prefix}${name}_joint" type="fixed">
<joint name="${device_namespace}_bottom_screw_to_${device_namespace}_joint" type="fixed">
<origin xyz="${d435_mesh_x_offset} ${d435_cam_depth_py} ${d435_cam_depth_pz}"
rpy="0.0 0.0 0.0" />
<parent link="${prefix}${name}_bottom_screw_frame" />
<child link="${prefix}${name}_link" />
<parent link="${device_namespace}_bottom_screw_frame" />
<child link="${device_namespace}_link" />
</joint>

<link name="${prefix}${name}_link">
<link name="${device_namespace}_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<geometry>
Expand All @@ -112,132 +102,130 @@
published. e.g. running the device in simulation -->
<xacro:if value="${use_nominal_extrinsics}">
<!-- camera depth joints and links -->
<joint name="${prefix}${name}_to_${prefix}${name}_depth_joint" type="fixed">
<joint name="${device_namespace}_to_${device_namespace}_depth_joint" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<parent link="${prefix}${name}_link" />
<child link="${prefix}${name}_depth_frame" />
<parent link="${device_namespace}_link" />
<child link="${device_namespace}_depth_frame" />
</joint>

<link name="${prefix}${name}_depth_frame" />
<link name="${device_namespace}_depth_frame" />

<joint name="${prefix}${name}_depth_to_${prefix}${name}_depth_optical_joint" type="fixed">
<joint name="${device_namespace}_depth_to_${device_namespace}_depth_optical_joint" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="${-pi/2.0} 0.0 ${-pi/2.0}" />
<parent link="${prefix}${name}_depth_frame" />
<child link="${prefix}${name}_depth_optical_frame" />
<parent link="${device_namespace}_depth_frame" />
<child link="${device_namespace}_depth_optical_frame" />
</joint>

<link name="${prefix}${name}_depth_optical_frame" />
<link name="${device_namespace}_depth_optical_frame" />

<!-- camera left IR joints and links -->
<joint name="${prefix}${name}_to_${prefix}${name}_infra1_joint" type="fixed">
<joint name="${device_namespace}_to_${device_namespace}_infra1_joint" type="fixed">
<origin xyz="0.0 ${d435_cam_depth_to_infra1_offset} 0.0" rpy="0.0 0.0 0.0" />
<parent link="${prefix}${name}_link" />
<child link="${prefix}${name}_infra1_frame" />
<parent link="${device_namespace}_link" />
<child link="${device_namespace}_infra1_frame" />
</joint>

<link name="${prefix}${name}_infra1_frame" />
<link name="${device_namespace}_infra1_frame" />

<joint name="${prefix}${name}_infra1_to_${prefix}${name}_infra1_optical_joint" type="fixed">
<joint name="${device_namespace}_infra1_to_${device_namespace}_infra1_optical_joint" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="${-pi/2.0} 0.0 ${-pi/2.0}" />
<parent link="${prefix}${name}_infra1_frame" />
<child link="${prefix}${name}_infra1_optical_frame" />
<parent link="${device_namespace}_infra1_frame" />
<child link="${device_namespace}_infra1_optical_frame" />
</joint>

<link name="${prefix}${name}_infra1_optical_frame" />
<link name="${device_namespace}_infra1_optical_frame" />

<!-- camera right IR joints and links -->
<joint name="${prefix}${name}_to_${prefix}${name}_infra2_joint" type="fixed">
<joint name="${device_namespace}_to_${device_namespace}_infra2_joint" type="fixed">
<origin xyz="0.0 ${d435_cam_depth_to_infra2_offset} 0.0" rpy="0.0 0.0 0.0" />
<parent link="${prefix}${name}_link" />
<child link="${prefix}${name}_infra2_frame" />
<parent link="${device_namespace}_link" />
<child link="${device_namespace}_infra2_frame" />
</joint>

<link name="${prefix}${name}_infra2_frame" />
<link name="${device_namespace}_infra2_frame" />

<joint name="${prefix}${name}_infra2_to_${prefix}${name}_infra2_optical_joint" type="fixed">
<joint name="${device_namespace}_infra2_to_${device_namespace}_infra2_optical_joint" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="${-pi/2.0} 0.0 ${-pi/2.0}" />
<parent link="${prefix}${name}_infra2_frame" />
<child link="${prefix}${name}_infra2_optical_frame" />
<parent link="${device_namespace}_infra2_frame" />
<child link="${device_namespace}_infra2_optical_frame" />
</joint>

<link name="${prefix}${name}_infra2_optical_frame" />
<link name="${device_namespace}_infra2_optical_frame" />

<!-- camera color joints and links -->
<joint name="${prefix}${name}_to_${prefix}${name}_color_joint" type="fixed">
<joint name="${device_namespace}_to_${device_namespace}_color_joint" type="fixed">
<origin xyz="0.0 ${d435_cam_depth_to_color_offset} 0.0" rpy="0.0 0.0 0.0" />
<parent link="${prefix}${name}_link" />
<child link="${prefix}${name}_color_frame" />
<parent link="${device_namespace}_link" />
<child link="${device_namespace}_color_frame" />
</joint>

<link name="${prefix}${name}_color_frame" />
<link name="${device_namespace}_color_frame" />

<joint name="${prefix}${name}_color_to_${prefix}${name}_color_optical_joint" type="fixed">
<joint name="${device_namespace}_color_to_${device_namespace}_color_optical_joint" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="${-pi/2.0} 0.0 ${-pi/2.0}" />
<parent link="${prefix}${name}_color_frame" />
<child link="${prefix}${name}_color_optical_frame" />
<parent link="${device_namespace}_color_frame" />
<child link="${device_namespace}_color_optical_frame" />
</joint>

<link name="${prefix}${name}_color_optical_frame" />
<link name="${device_namespace}_color_optical_frame" />
</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 for D435 - different frames and fovs can be set -->
<gazebo reference="${prefix}${name}_link">
<!-- 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>${ns}${topic}/color/image_raw</topic>
<visualize>false</visualize>

<ignition_frame_id>${prefix}${name}_color_optical_frame</ignition_frame_id>
<horizontal_fov>${69.0/180.0*pi}</horizontal_fov>
<!-- 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="${device_namespace}_link">
<!-- https://github.com/IntelRealSense/realsense-ros#published-topics -->
<sensor type="camera" name="${ns}${device_namespace}_intel_realsense_d435_color">
<always_on>true</always_on>
<update_rate>30.0</update_rate>

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

<ignition_frame_id>${device_namespace}_color_optical_frame</ignition_frame_id>
<horizontal_fov>${69.0/180.0*pi}</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300.0</far>
</clip>
<ros>
<namespace>${ns}${device_namespace}</namespace>
</ros>
</sensor>

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

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

<ignition_frame_id>${device_namespace}_depth_optical_frame</ignition_frame_id>
<camera>
<horizontal_fov>${87.0/180.0*pi}</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
<format>R_FLOAT32</format>
</image>
<clip>
<near>0.02</near>
<far>300.0</far>
<near>0.28</near>
<far>8.0</far>
</clip>
<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>

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

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

<ignition_frame_id>${prefix}${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>
<ros>
<namespace>${ns}</namespace>
</ros>
</sensor>
</gazebo>
</xacro:if>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.005</stddev>
</noise>
</camera>
<ros>
<namespace>${ns}${device_namespace}</namespace>
</ros>
</sensor>
</gazebo>
</xacro:macro>
</robot>
6 changes: 3 additions & 3 deletions urdf/orbbec_astra.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="orbbec_astra"
params="parent_link xyz rpy
device_namespace:=camera
namespace:=None">
namespace:=None
device_namespace:=camera">

<xacro:if value="${namespace == 'None'}">
<xacro:property name="ns" value="" />
Expand Down Expand Up @@ -143,7 +143,7 @@
</noise>
</camera>
<ros>
<namespace>${ns}</namespace>
<namespace>${ns}${device_namespace}</namespace>
</ros>
</sensor>
</gazebo>
Expand Down
Loading

0 comments on commit 20e6ae3

Please sign in to comment.