Skip to content

Commit

Permalink
Refactor
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Nov 16, 2023
1 parent 3fefa6e commit 1197035
Show file tree
Hide file tree
Showing 6 changed files with 111 additions and 111 deletions.
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>
28 changes: 14 additions & 14 deletions urdf/ouster_os1_32.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -18,19 +18,19 @@
</xacro:unless>

<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}ouster_os1_32_joint" type="fixed">
<joint name="${parent_link.rstrip('_link')}_to_${prefix}ouster_os1_32_joint" type="fixed">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent_link}" />
<child link="${tf_prefix_ext}ouster_os1_32_link" />
<child link="${prefix}ouster_os1_32_link" />
</joint>

<link name="${tf_prefix_ext}ouster_os1_32_link">
<link name="${prefix}ouster_os1_32_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<geometry>
Expand All @@ -54,16 +54,16 @@
</inertial>
</link>

<joint name="${tf_prefix_ext}ouster_os1_32_to_${tf_prefix_ext}${frame_id.rstrip('_link')}_joint" type="fixed">
<joint name="${prefix}ouster_os1_32_to_${prefix}${frame_id.rstrip('_link')}_joint" type="fixed">
<origin xyz="0.0 0.0 0.03618" rpy="0.0 0.0 0.0" />
<parent link="${tf_prefix_ext}ouster_os1_32_link" />
<child link="${tf_prefix_ext}${frame_id}" />
<parent link="${prefix}ouster_os1_32_link" />
<child link="${prefix}${frame_id}" />
</joint>

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

<gazebo reference="${tf_prefix_ext}${frame_id}">
<sensor type="${ray_type}" name="${tf_prefix_ext}ouster_os1_32_sensor">
<gazebo reference="${prefix}${frame_id}">
<sensor type="${ray_type}" name="${prefix}ouster_os1_32_sensor">
<visualize>false</visualize>
<ray>
<scan>
Expand Down Expand Up @@ -95,15 +95,15 @@

<update_rate>20.0</update_rate>

<plugin name="${tf_prefix_ext}ouster_os1_32_${ray_type}" filename="libgazebo_ros_ray_sensor.so">
<plugin name="${prefix}ouster_os1_32_${ray_type}" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace></namespace>
<remapping>~/out:=${topic}</remapping>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
<frame_name>${tf_prefix_ext}${frame_id}</frame_name>
<frame_name>${prefix}${frame_id}</frame_name>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
</robot>
34 changes: 17 additions & 17 deletions urdf/slamtec_rplidar_a2.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,10 @@
</xacro:unless>

<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>

<!--values of max distance are based on tradeoff values between best and worst case scenarios -->
Expand All @@ -60,13 +60,13 @@
<xacro:property name="mesh" value="slamtec_rplidar_ax.dae" />
</xacro:if>

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

<link name="${tf_prefix_ext}slamtec_rplidar_a2_link">
<link name="${prefix}slamtec_rplidar_a2_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<geometry>
Expand All @@ -90,21 +90,21 @@
</inertial>
</link>

<joint name="${tf_prefix_ext}slamtec_rplidar_a2_to_${tf_prefix_ext}${frame_id.rstrip('_link')}_joint" type="fixed">
<joint name="${prefix}slamtec_rplidar_a2_to_${prefix}${frame_id.rstrip('_link')}_joint" type="fixed">
<origin xyz="0.0 0.0 0.031" rpy="0.0 0.0 ${pi}" />
<parent link="${tf_prefix_ext}slamtec_rplidar_a2_link" />
<child link="${tf_prefix_ext}${frame_id}" />
<parent link="${prefix}slamtec_rplidar_a2_link" />
<child link="${prefix}${frame_id}" />
</joint>

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

<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<gazebo reference="${tf_prefix_ext}${frame_id}">
<sensor type="${ray_type}" name="${tf_prefix_ext}rplidar_a2_sensor">
<gazebo reference="${prefix}${frame_id}">
<sensor type="${ray_type}" name="${prefix}rplidar_a2_sensor">

<topic>${topic}</topic>
<frame_id>${tf_prefix_ext}${frame_id}</frame_id>
<ignition_frame_id>${tf_prefix_ext}${frame_id}</ignition_frame_id>
<frame_id>${prefix}${frame_id}</frame_id>
<ignition_frame_id>${prefix}${frame_id}</ignition_frame_id>

<update_rate>10.0</update_rate>
<ray>
Expand Down Expand Up @@ -139,8 +139,8 @@
</xacro:if>

<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<gazebo reference="${tf_prefix_ext}${frame_id}">
<sensor type="${ray_type}" name="${tf_prefix_ext}slamtec_rplidar_a2_sensor">
<gazebo reference="${prefix}${frame_id}">
<sensor type="${ray_type}" name="${prefix}slamtec_rplidar_a2_sensor">
<visualize>false</visualize>
<ray>
<scan>
Expand Down Expand Up @@ -171,10 +171,10 @@
<remapping>~/out:=${topic}</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>${tf_prefix_ext}${frame_id}</frame_name>
<frame_name>${prefix}${frame_id}</frame_name>
</plugin>
</sensor>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>
</robot>
34 changes: 17 additions & 17 deletions urdf/slamtec_rplidar_a3.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -28,19 +28,19 @@
</xacro:unless>

<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}slamtec_rplidar_a3_joint" type="fixed">
<joint name="${parent_link.rstrip('_link')}_to_${prefix}slamtec_rplidar_a3_joint" type="fixed">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent_link}" />
<child link="${tf_prefix_ext}slamtec_rplidar_a3_link" />
<child link="${prefix}slamtec_rplidar_a3_link" />
</joint>

<link name="${tf_prefix_ext}slamtec_rplidar_a3_link">
<link name="${prefix}slamtec_rplidar_a3_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<geometry>
Expand All @@ -65,21 +65,21 @@
</inertial>
</link>

<joint name="${tf_prefix_ext}slamtec_rplidar_a3_to_${tf_prefix_ext}${frame_id.rstrip('_link')}_joint" type="fixed">
<joint name="${prefix}slamtec_rplidar_a3_to_${prefix}${frame_id.rstrip('_link')}_joint" type="fixed">
<origin xyz="0.0 0.0 0.031" rpy="0.0 0.0 ${pi}" />
<parent link="${tf_prefix_ext}slamtec_rplidar_a3_link" />
<child link="${tf_prefix_ext}${frame_id}" />
<parent link="${prefix}slamtec_rplidar_a3_link" />
<child link="${prefix}${frame_id}" />
</joint>

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

<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<gazebo reference="${tf_prefix_ext}${frame_id}">
<sensor type="${ray_type}" name="${tf_prefix_ext}rplidar_a3_sensor">
<gazebo reference="${prefix}${frame_id}">
<sensor type="${ray_type}" name="${prefix}rplidar_a3_sensor">

<topic>${topic}</topic>
<frame_id>${tf_prefix_ext}${frame_id}</frame_id>
<ignition_frame_id>${tf_prefix_ext}${frame_id}</ignition_frame_id>
<frame_id>${prefix}${frame_id}</frame_id>
<ignition_frame_id>${prefix}${frame_id}</ignition_frame_id>

<update_rate>10.0</update_rate>
<ray>
Expand Down Expand Up @@ -115,8 +115,8 @@
</xacro:if>

<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<gazebo reference="${tf_prefix_ext}${frame_id}">
<sensor type="${ray_type}" name="${tf_prefix_ext}slamtec_rplidar_a3_sensor">
<gazebo reference="${prefix}${frame_id}">
<sensor type="${ray_type}" name="${prefix}slamtec_rplidar_a3_sensor">
<visualize>false</visualize>
<ray>
<scan>
Expand Down Expand Up @@ -148,10 +148,10 @@
<remapping>~/out:=${topic}</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>${tf_prefix_ext}${frame_id}</frame_name>
<frame_name>${prefix}${frame_id}</frame_name>
</plugin>
</sensor>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>
</robot>
Loading

0 comments on commit 1197035

Please sign in to comment.