Skip to content

Commit

Permalink
added ouster os1 and os0
Browse files Browse the repository at this point in the history
  • Loading branch information
delihus committed May 17, 2024
1 parent cc857d2 commit c86e9e8
Show file tree
Hide file tree
Showing 5 changed files with 142 additions and 14 deletions.
5 changes: 5 additions & 0 deletions launch/gz_components.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,12 @@ def get_launch_descriptions_from_yaml_node(
components_types_with_names = {
"LDR01": "slamtec_rplidar",
"LDR06": "slamtec_rplidar",
"LDR10": "ouster_os",
"LDR11": "ouster_os",
"LDR12": "ouster_os",
"LDR13": "ouster_os",
"LDR14": "ouster_os",
"LDR15": "ouster_os",
"LDR20": "velodyne",
"CAM01": "orbbec_astra",
"MAN01": "ur",
Expand Down
File renamed without changes.
5 changes: 5 additions & 0 deletions test/test_components_xacro.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,12 @@
components_types_with_names = {
"LDR01": ["slamtec_rplidar_s1", "laser", "laser", "slamtec_rplidar_s1_sensor"],
"LDR06": ["slamtec_rplidar_s3", "laser", "laser", "slamtec_rplidar_s3_sensor"],
"LDR10": ["ouster_os0_32", "os_lidar", "os_lidar", "ouster_os0_32_sensor"],
"LDR11": ["ouster_os0_64", "os_lidar", "os_lidar", "ouster_os0_64_sensor"],
"LDR12": ["ouster_os0_128", "os_lidar", "os_lidar", "ouster_os0_128_sensor"],
"LDR13": ["ouster_os1_32", "os_lidar", "os_lidar", "ouster_os1_32_sensor"],
"LDR14": ["ouster_os1_64", "os_lidar", "os_lidar", "ouster_os1_64_sensor"],
"LDR15": ["ouster_os1_128", "os_lidar", "os_lidar", "ouster_os1_128_sensor"],
"LDR20": ["velodyne_puck", "velodyne", "velodyne", "velodyne_puck_sensor"],
"CAM01": ["orbbec_astra", "link", "link", "orbbec_astra_color"],
"MAN01": ["ur3e", "base_link", "", ""],
Expand Down
85 changes: 83 additions & 2 deletions urdf/components.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -71,18 +71,99 @@
/>
</xacro:if>

<xacro:if value="${type == 'LDR10'}">
<xacro:include
filename="$(find ros_components_description)/urdf/ouster_os01.urdf.xacro"
ns="lidar"
/>

<xacro:lidar.ouster_os01
parent_link="${parent_link}"
xyz="${xyz}"
rpy="${rpy}"
namespace="${robot_namespace}"
device_namespace="${device_namespace}"
model="os0_32"
/>
</xacro:if>

<xacro:if value="${type == 'LDR11'}">
<xacro:include
filename="$(find ros_components_description)/urdf/ouster_os01.urdf.xacro"
ns="lidar"
/>

<xacro:lidar.ouster_os01
parent_link="${parent_link}"
xyz="${xyz}"
rpy="${rpy}"
namespace="${robot_namespace}"
device_namespace="${device_namespace}"
model="os0_64"
/>
</xacro:if>

<xacro:if value="${type == 'LDR12'}">
<xacro:include
filename="$(find ros_components_description)/urdf/ouster_os01.urdf.xacro"
ns="lidar"
/>

<xacro:lidar.ouster_os01
parent_link="${parent_link}"
xyz="${xyz}"
rpy="${rpy}"
namespace="${robot_namespace}"
device_namespace="${device_namespace}"
model="os0_128"
/>
</xacro:if>

<xacro:if value="${type == 'LDR13'}">
<xacro:include
filename="$(find ros_components_description)/urdf/ouster_os1_32.urdf.xacro"
filename="$(find ros_components_description)/urdf/ouster_os01.urdf.xacro"
ns="lidar"
/>

<xacro:lidar.ouster_os01
parent_link="${parent_link}"
xyz="${xyz}"
rpy="${rpy}"
namespace="${robot_namespace}"
device_namespace="${device_namespace}"
model="os1_32"
/>
</xacro:if>

<xacro:if value="${type == 'LDR14'}">
<xacro:include
filename="$(find ros_components_description)/urdf/ouster_os01.urdf.xacro"
ns="lidar"
/>

<xacro:lidar.ouster_os01
parent_link="${parent_link}"
xyz="${xyz}"
rpy="${rpy}"
namespace="${robot_namespace}"
device_namespace="${device_namespace}"
model="os1_64"
/>
</xacro:if>

<xacro:if value="${type == 'LDR15'}">
<xacro:include
filename="$(find ros_components_description)/urdf/ouster_os01.urdf.xacro"
ns="lidar"
/>

<xacro:lidar.ouster_os1_32
<xacro:lidar.ouster_os01
parent_link="${parent_link}"
xyz="${xyz}"
rpy="${rpy}"
namespace="${robot_namespace}"
device_namespace="${device_namespace}"
model="os1_128"
/>
</xacro:if>

Expand Down
61 changes: 49 additions & 12 deletions urdf/ouster_os1_32.urdf.xacro → urdf/ouster_os01.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,10 +1,47 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="ouster_os1_32"
<xacro:macro name="ouster_os01"
params="parent_link xyz rpy
model:=os1_32
namespace:=None
device_namespace:=None">

<xacro:if value="${model == 'os0_32'}">
<xacro:property name="vfov" value="${radians(90.0)}" scope="parent" />
<xacro:property name="lidar_range" value="50" scope="parent"/>
<xacro:property name="layers" value="32" scope="parent"/>
</xacro:if>

<xacro:if value="${model == 'os0_64'}">
<xacro:property name="vfov" value="${radians(90.0)}" scope="parent" />
<xacro:property name="lidar_range" value="50" scope="parent" />
<xacro:property name="layers" value="64" scope="parent" />
</xacro:if>

<xacro:if value="${model == 'os0_128'}">
<xacro:property name="vfov" value="${radians(90.0)}" scope="parent" />
<xacro:property name="lidar_range" value="50" scope="parent" />
<xacro:property name="layers" value="128" scope="parent" />
</xacro:if>

<xacro:if value="${model == 'os1_32'}">
<xacro:property name="vfov" value="${radians(45.0)}" scope="parent" />
<xacro:property name="lidar_range" value="120" scope="parent" />
<xacro:property name="layers" value="32" scope="parent" />
</xacro:if>

<xacro:if value="${model == 'os1_64'}">
<xacro:property name="vfov" value="${radians(45.0)}" scope="parent" />
<xacro:property name="lidar_range" value="120" scope="parent" />
<xacro:property name="layers" value="64" scope="parent" />
</xacro:if>

<xacro:if value="${model == 'os1_128'}">
<xacro:property name="vfov" value="${radians(45.0)}" scope="parent" />
<xacro:property name="lidar_range" value="120" scope="parent" />
<xacro:property name="layers" value="128" scope="parent" />
</xacro:if>

<xacro:if value="${namespace == 'None'}">
<xacro:property name="ns" value="" />
</xacro:if>
Expand All @@ -26,17 +63,17 @@
<xacro:property name="prefix" value="${device_namespace}_" />
</xacro:unless>

<joint name="${parent_link.rstrip('_link')}_to_${prefix}ouster_os1_32_joint" type="fixed">
<joint name="${parent_link.rstrip('_link')}_to_${prefix}ouster_${model}_joint" type="fixed">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent_link}" />
<child link="${prefix}ouster_os1_32_link" />
<child link="${prefix}ouster_${model}_link" />
</joint>

<link name="${prefix}ouster_os1_32_link">
<link name="${prefix}ouster_${model}_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<geometry>
<mesh filename="package://ros_components_description/meshes/ouster_os1_32.dae" />
<mesh filename="package://ros_components_description/meshes/ouster_os01.dae" />
</geometry>
</visual>

Expand All @@ -56,9 +93,9 @@
</inertial>
</link>

<joint name="${prefix}ouster_os1_32_to_${prefix}os_lidar_joint" type="fixed">
<joint name="${prefix}ouster_${model}_to_${prefix}os_lidar_joint" type="fixed">
<origin xyz="0.0 0.0 0.03618" rpy="0.0 0.0 0.0" />
<parent link="${prefix}ouster_os1_32_link" />
<parent link="${prefix}ouster_${model}_link" />
<child link="${prefix}os_lidar" />
</joint>

Expand All @@ -67,7 +104,7 @@
<gazebo reference="${prefix}os_lidar">
<!-- gpu_lidar has to be set, CPU lidar doesn't work in ignition -
https://github.com/gazebosim/gz-sensors/issues/26 -->
<sensor type="gpu_lidar" name="${ns}${prefix}ouster_os1_32_sensor">
<sensor type="gpu_lidar" name="${ns}${prefix}ouster_${model}_sensor">
<visualize>false</visualize>
<ray>
<scan>
Expand All @@ -78,15 +115,15 @@
<max_angle>${pi}</max_angle>
</horizontal>
<vertical>
<samples>32</samples>
<samples>${layers}</samples>
<resolution>1</resolution>
<min_angle>-${22.5/180.0*pi}</min_angle>
<max_angle>${22.5/180.0*pi}</max_angle>
<min_angle>${vfov/-2.0}</min_angle>
<max_angle>${vfov/2.0}</max_angle>
</vertical>
</scan>
<range>
<min>0.8</min>
<max>120.0</max>
<max>${lidar_range}</max>
<resolution>0.003</resolution>
</range>

Expand Down

0 comments on commit c86e9e8

Please sign in to comment.