Skip to content

Commit

Permalink
Add prefix (#36)
Browse files Browse the repository at this point in the history
* file -> package

* Add prefix

* update readme
  • Loading branch information
rafal-gorecki authored Jan 4, 2024
1 parent 8b934bc commit 4f1bc6f
Show file tree
Hide file tree
Showing 11 changed files with 229 additions and 209 deletions.
18 changes: 11 additions & 7 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
# ros_components_description

URDF models of sensors and other components offered alongside with Husarion robots

## Including sensor

First build the package by running:
``` bash

```bash
# create workspace folder and clone ros_components_description
mkdir -p ros2_ws/src
cd ros2_ws
Expand All @@ -25,7 +27,8 @@ colcon build
```

To include the sensor, use the following code:
``` xml

```xml
<!-- include file with definition of xacro macro of sensor -->
<xacro:include filename="$(find ros_components_description)/urdf/slamtec_rplidar_s1.urdf.xacro" ns="lidar" />

Expand All @@ -39,15 +42,16 @@ To include the sensor, use the following code:
```

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 default of manufacturer**] name of topic at which simulated sensor will publish data.
- `frame_id` [*string*, default: **same as default of manufacturer**] name of final tf to which sensor will be attached. Should match one from message published by sensor.
- `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).
- **gazebo-classic** used to select [Gazebo Classic](https://classic.gazebosim.org/).
- **ignition-gazebo** used to select [Ignition Gazebo](https://gazebosim.org/home).

Some sensors can define their specific parameters. Refer to their definition for more info.
Some sensors can define their specific parameters. Refer to their definition for more info.
98 changes: 53 additions & 45 deletions urdf/intel_realsense_d435.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,22 @@
# limitations under the License.
-->

<robot name="intel_camera" xmlns:xacro="http://ros.org/wiki/xacro">
<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
simulation_engine:=ignition-gazebo">

<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 @@ -54,22 +62,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_${name}_bottom_screw_joint" type="fixed">
<joint name="${parent_link.rstrip('_link')}_to_${prefix}${name}_bottom_screw_joint" type="fixed">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent_link}" />
<child link="${name}_bottom_screw_frame" />
<child link="${prefix}${name}_bottom_screw_frame" />
</joint>

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

<joint name="${name}_bottom_screw_to_${name}_joint" type="fixed">
<joint name="${prefix}${name}_bottom_screw_to_${prefix}${name}_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="${name}_bottom_screw_frame" />
<child link="${name}_link" />
<parent link="${prefix}${name}_bottom_screw_frame" />
<child link="${prefix}${name}_link" />
</joint>

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

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

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

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

<!-- camera left IR joints and links -->
<joint name="${name}_to_${name}_infra1_joint" type="fixed">
<joint name="${prefix}${name}_to_${prefix}${name}_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="${name}_link" />
<child link="${name}_infra1_frame" />
<parent link="${prefix}${name}_link" />
<child link="${prefix}${name}_infra1_frame" />
</joint>

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

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

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

<!-- camera right IR joints and links -->
<joint name="${name}_to_${name}_infra2_joint" type="fixed">
<joint name="${prefix}${name}_to_${prefix}${name}_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="${name}_link" />
<child link="${name}_infra2_frame" />
<parent link="${prefix}${name}_link" />
<child link="${prefix}${name}_infra2_frame" />
</joint>

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

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

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

<!-- camera color joints and links -->
<joint name="${name}_to_${name}_color_joint" type="fixed">
<joint name="${prefix}${name}_to_${prefix}${name}_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="${name}_link" />
<child link="${name}_color_frame" />
<parent link="${prefix}${name}_link" />
<child link="${prefix}${name}_color_frame" />
</joint>

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

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

<link name="${name}_color_optical_frame" />
<link name="${prefix}${name}_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="${name}_link">
<sensor type="camera" name="${name}_color">
<gazebo reference="${prefix}${name}_link">
<sensor type="camera" name="${prefix}${name}_color">
<always_on>true</always_on>
<update_rate>30.0</update_rate>

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

<ignition_frame_id>${name}_color_optical_frame</ignition_frame_id>
<ignition_frame_id>${prefix}${name}_color_optical_frame</ignition_frame_id>
<horizontal_fov>${69.0/180.0*pi}</horizontal_fov>
<image>
<width>1280</width>
Expand All @@ -188,14 +196,14 @@
</clip>
</sensor>

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

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

<ignition_frame_id>${name}_depth_optical_frame</ignition_frame_id>
<ignition_frame_id>${prefix}${name}_depth_optical_frame</ignition_frame_id>
<camera>
<horizontal_fov>${87.0/180.0*pi}</horizontal_fov>
<image>
Expand Down
62 changes: 31 additions & 31 deletions urdf/orbbec_astra.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,19 +7,19 @@
simulation_engine:=gazebo-classic">

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

<joint name="${parent_link.rstrip('_link')}_to_${tf_prefix_ext}${camera_name}_orbbec_astra_joint" type="fixed">
<joint name="${parent_link.rstrip('_link')}_to_${prefix}${camera_name}_orbbec_astra_joint" type="fixed">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent_link}" />
<child link="${tf_prefix_ext}${camera_name}_orbbec_astra_link" />
<child link="${prefix}${camera_name}_orbbec_astra_link" />
</joint>

<link name="${tf_prefix_ext}${camera_name}_orbbec_astra_link">
<link name="${prefix}${camera_name}_orbbec_astra_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<geometry>
Expand Down Expand Up @@ -52,50 +52,50 @@
</inertial>
</link>

<joint name="${parent_link.rstrip('_link')}_to_${tf_prefix_ext}${camera_name}_color_joint" type="fixed">
<joint name="${parent_link.rstrip('_link')}_to_${prefix}${camera_name}_color_joint" type="fixed">
<origin xyz="-0.002 0.0125 0.03325" rpy="-0.003 0.0 -0.003" />
<parent link="${parent_link}" />
<child link="${tf_prefix_ext}${camera_name}_color_frame" />
<child link="${prefix}${camera_name}_color_frame" />
</joint>

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

<joint name="${parent_link.rstrip('_link')}_to_${tf_prefix_ext}${camera_name}_depth_joint" type="fixed">
<joint name="${parent_link.rstrip('_link')}_to_${prefix}${camera_name}_depth_joint" type="fixed">
<origin xyz="0.0 0.0 0.03325" rpy="0.0 0.0 0.0" />
<parent link="${parent_link}" />
<child link="${tf_prefix_ext}${camera_name}_depth_frame" />
<child link="${prefix}${camera_name}_depth_frame" />
</joint>

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

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

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

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

<link name="${tf_prefix_ext}${camera_name}_color_optical_frame" />
<link name="${prefix}${camera_name}_color_optical_frame" />

<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<gazebo reference="${tf_prefix_ext}${camera_name}_orbbec_astra_link">
<sensor type="rgbd_camera" name="${tf_prefix_ext}${camera_name}_orbbec_astra_camera">
<gazebo reference="${prefix}${camera_name}_orbbec_astra_link">
<sensor type="rgbd_camera" name="${prefix}${camera_name}_orbbec_astra_camera">
<always_on>true</always_on>
<update_rate>20.0</update_rate>

<topic>${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 ${tf_prefix_ext}${camera_name}_color_optical_frame -->
<ignition_frame_id>${tf_prefix_ext}${camera_name}_depth_optical_frame</ignition_frame_id>
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>

<camera name="${tf_prefix_ext}camera">
<camera name="${prefix}camera">
<horizontal_fov>${60.0/180.0*pi}</horizontal_fov>
<image>
<width>640</width>
Expand All @@ -117,12 +117,12 @@
</xacro:if>

<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<gazebo reference="${tf_prefix_ext}orbbec_astra_link">
<sensor type="depth" name="${tf_prefix_ext}orbbec_astra_camera">
<gazebo reference="${prefix}orbbec_astra_link">
<sensor type="depth" name="${prefix}orbbec_astra_camera">
<always_on>true</always_on>
<update_rate>20.0</update_rate>

<camera name="${tf_prefix_ext}camera">
<camera name="${prefix}camera">
<horizontal_fov>${60.0/180.0*pi}</horizontal_fov>
<image>
<format>R8G8B8</format>
Expand All @@ -131,7 +131,7 @@
</image>
</camera>

<plugin name="${tf_prefix_ext}orbbec_astra_camera" filename="libgazebo_ros_camera.so">
<plugin name="${prefix}orbbec_astra_camera" filename="libgazebo_ros_camera.so">
<ros>
<namespace>orbbec_astra_camera</namespace>
<remapping>custom_camera/image_raw:=rgb/image_raw</remapping>
Expand All @@ -141,8 +141,8 @@
<remapping>custom_camera/points:=depth/points</remapping>
</ros>

<camera_name>${tf_prefix_ext}camera</camera_name>
<frame_name>${tf_prefix_ext}${frame_id}</frame_name>
<camera_name>${prefix}camera</camera_name>
<frame_name>${prefix}${frame_id}</frame_name>
<hack_baseline>0.07</hack_baseline>

<min_depth>0.6</min_depth>
Expand All @@ -152,4 +152,4 @@
</gazebo>
</xacro:if>
</xacro:macro>
</robot>
</robot>
Loading

0 comments on commit 4f1bc6f

Please sign in to comment.