Skip to content

Commit

Permalink
Rplidar-merge (#52)
Browse files Browse the repository at this point in the history
* Rplidar-merge

* Fix urdf
  • Loading branch information
rafal-gorecki committed Jun 14, 2024
1 parent a647358 commit 59f8172
Show file tree
Hide file tree
Showing 10 changed files with 290 additions and 579 deletions.
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,10 @@ To include the sensor, use the following code:

```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" />
<xacro:include filename="$(find ros_components_description)/urdf/slamtec_rplidar.urdf.xacro" ns="lidar" />

<!-- evaluate the macro and place the sensor on robot -->
<xacro:lidar.slamtec_rplidar_s1
<xacro:lidar.slamtec_rplidar
parent_link="cover_link"
xyz="0.0 0.0 0.0"
rpy="0.0 0.0 0.0" />
Expand Down
4 changes: 2 additions & 2 deletions test/test_components_xacro.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@

# Type: [model_link, link_name, sensor_link_name, sensor_name]
components_types_with_names = {
"LDR01": ["slamtec_rplidar_s1", "laser", "laser", "slamtec_rplidar_s1_sensor"],
"LDR06": ["slamtec_rplidar_s3", "laser", "laser", "slamtec_rplidar_s3_sensor"],
"LDR01": ["slamtec_rplidar_s1", "laser", "laser", "slamtec_rplidar_sensor"],
"LDR06": ["slamtec_rplidar_s3", "laser", "laser", "slamtec_rplidar_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"],
Expand Down
26 changes: 9 additions & 17 deletions urdf/components.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -71,33 +71,25 @@
/>
</xacro:if>

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

<xacro:lidar.slamtec_rplidar_s1
parent_link="${parent_link}"
xyz="${xyz}"
rpy="${rpy}"
namespace="${ns}"
device_namespace="${device_namespace}"
/>
</xacro:if>
<xacro:property name="rplidar_models_dict"
value="${dict ([
('LDR01', 's1'),
('LDR06', 's3'),
])}" />

<xacro:if value="${type == 'LDR06'}">
<xacro:if value="${type in rplidar_models_dict}">
<xacro:include
filename="$(find ros_components_description)/urdf/slamtec_rplidar_s3.urdf.xacro"
filename="$(find ros_components_description)/urdf/slamtec_rplidar.urdf.xacro"
ns="lidar"
/>

<xacro:lidar.slamtec_rplidar_s3
<xacro:lidar.slamtec_rplidar
parent_link="${parent_link}"
xyz="${xyz}"
rpy="${rpy}"
namespace="${ns}"
device_namespace="${device_namespace}"
model="${rplidar_models_dict[type]}"
/>
</xacro:if>

Expand Down
6 changes: 3 additions & 3 deletions urdf/intel_realsense_d435.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@
<xacro:property name="d435_cam_depth_to_infra2_offset" value="-0.050" />
<xacro:property name="d435_cam_depth_to_color_offset" value="0.015" />

<!-- The following values model the aluminum peripherial case for the
<!-- The following values model the aluminum peripheral case for the
D435 camera, with the camera joint represented by the actual
peripherial camera tripod mount -->
peripheral camera tripod mount -->
<xacro:property name="d435_cam_width" value="0.090" />
<xacro:property name="d435_cam_height" value="0.025" />
<xacro:property name="d435_cam_depth" value="0.02505" />
Expand All @@ -52,7 +52,7 @@
<xacro:property name="d435_mesh_x_offset"
value="${d435_cam_mount_from_center_offset-d435_glass_to_front-d435_zero_depth_to_glass}" />

<!-- The following offset is relative the the physical D435 camera peripherial
<!-- The following offset is relative the the physical D435 camera peripheral
camera tripod mount -->
<xacro:property name="d435_cam_depth_px" value="${d435_cam_mount_from_center_offset}" />
<xacro:property name="d435_collision_offset_x" value="0.00824" />
Expand Down
274 changes: 274 additions & 0 deletions urdf/slamtec_rplidar.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,274 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="slamtec_rplidar"
params="parent_link xyz rpy
namespace:=None
device_namespace:=None
model:=s3">

<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="${device_namespace == 'None'}">
<xacro:property name="device_ns" value="" />
</xacro:if>
<xacro:unless value="${device_namespace == 'None'}">
<xacro:property name="device_ns" value="${device_namespace}/" />
</xacro:unless>

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

<xacro:if value="${model == 's3'}">
<!-- Spec: https://www.slamtec.ai/wp-content/uploads/2023/11/SLAMTEC_rplidar_datasheet_S3_v1.0_en.pdf -->
<xacro:property name="samples" value="3000" />
<xacro:property name="dist_min" value="0.05" />
<xacro:property name="dist_max" value="40.0" />
<xacro:property name="dist_res" value="0.01" />
<xacro:property name="std_dev" value="0.03" />
<xacro:property name="mesh" value="slamtec_rplidar_s3.dae" />
<xacro:property name="collision">
<origin xyz="0.0 0.0 ${0.0413/2.0}" rpy="0.0 0.0 0.0" />
<geometry>
<box size="0.0556 0.0556 0.0413" />
</geometry>
</xacro:property>
<xacro:property name="inertial">
<origin xyz="0.0 0.0 ${0.0413/2.0 + 0.0018237}" rpy="0.0 0.0 0.0" />
<mass value="0.115033" />
<inertia ixx="0.00004115765" ixy="0.0" ixz="0.0"
iyy="0.00004115765" iyz="0.0"
izz="0.00004956023" />
</xacro:property>
<xacro:property name="joint">
<origin xyz="0.0 0.0 0.0305" rpy="0.0 0.0 ${pi}" />
</xacro:property>
</xacro:if>

<xacro:if value="${model == 's2'}">
<!-- Spec: https://www.slamtec.ai/wp-content/uploads/2023/11/SLAMTEC_rplidar_datasheet_S2M1_v1.4_en.pdf -->
<xacro:property name="samples" value="3000" />
<xacro:property name="dist_min" value="0.05" />
<xacro:property name="dist_max" value="30.0" />
<xacro:property name="dist_res" value="0.013" />
<xacro:property name="std_dev" value="0.03" />
<xacro:property name="mesh" value="slamtec_rplidar_s2.dae" />
<xacro:property name="collision">
<origin xyz="0.0 0.0 ${0.038857/2.0}" rpy="0.0 0.0 0.0" />
<geometry>
<box size="0.077 0.076856 0.038857" />
</geometry>
</xacro:property>
<xacro:property name="inertial">
<origin xyz="0.0 -0.000021 ${0.038857/2.0 + 0.0017953}" rpy="0.0 0.0 0.0" />
<mass value="0.104949" />
<inertia ixx="0.00005071491" ixy="0.0" ixz="0.0"
iyy="0.00005064080" iyz="0.0"
izz="0.000075682018" />
</xacro:property>
<xacro:property name="joint">
<origin xyz="0.0 0.0 0.0285" rpy="0.0 0.0 ${pi}" />
</xacro:property>
</xacro:if>

<xacro:if value="${model == 's1'}">
<!-- Spec: https://www.slamtec.com/en/Lidar/S1Spec -->
<xacro:property name="samples" value="920" />
<xacro:property name="dist_min" value="0.04" />
<xacro:property name="dist_max" value="40.0" />
<xacro:property name="dist_res" value="0.03" />
<xacro:property name="std_dev" value="0.05" />
<xacro:property name="mesh" value="slamtec_rplidar_s1.dae" />
<xacro:property name="collision">
<origin xyz="0.0 0.0 ${0.0195/2.0}" rpy="0.0 0.0 0.0" />
<geometry>
<box size="0.0555 0.0555 0.0195" />
</geometry>
</xacro:property>
<xacro:property name="inertial">
<origin xyz="0.0 0.0 ${0.0555/2.0}" rpy="0.0 0.0 0.0" />
<mass value="0.105" />
<inertia ixx="0.000049654" ixy="0.0" ixz="0.0"
iyy="0.000049654" iyz="0.0"
izz="0.000053884" />
</xacro:property>
<xacro:property name="joint">
<origin xyz="0.0 0.0 0.04" rpy="0.0 0.0 ${pi}" />
</xacro:property>
</xacro:if>

<xacro:if value="${model == 'a3'}">
<!-- Spec: https://www.slamtec.ai/wp-content/uploads/2023/11/LD310_SLAMTEC_rplidar_datasheet_A3M1_v1.9_en.pdf -->
<xacro:property name="samples" value="1600" />
<xacro:property name="dist_min" value="0.2" />
<xacro:property name="dist_max" value="25.0" />
<xacro:property name="dist_res" value="0.03" />
<xacro:property name="std_dev" value="0.05" />
<xacro:property name="mesh" value="slamtec_rplidar_a3.dae" />
<xacro:property name="collision">
<origin xyz="0.0 0.0 ${0.041/2.0}" rpy="0.0 0.0 0.0" />
<geometry>
<cylinder radius="${0.076/2.0}" length="0.041" />
</geometry>
</xacro:property>
<xacro:property name="inertial">
<origin xyz="0.0 0.0 ${0.041/2.0}" rpy="0.0 0.0 0.0" />
<mass value="0.190" />
<inertia ixx="0.000095206" ixy="0.0" ixz="0.0"
iyy="0.000095206" iyz="0.0"
izz="0.00013718" />
</xacro:property>
<xacro:property name="joint">
<origin xyz="0.0 0.0 0.031" rpy="0.0 0.0 ${pi}" />
</xacro:property>
</xacro:if>

<xacro:if value="${model == 'a2m12'}">
<!-- Spec: https://www.slamtec.ai/wp-content/uploads/2023/11/LD310_SLAMTEC_rplidar_datasheet_A2M12_v1.0_en.pdf -->
<xacro:property name="samples" value="1600" />
<xacro:property name="dist_min" value="0.2" />
<xacro:property name="dist_max" value="12.0" />
<xacro:property name="dist_res" value="0.03" />
<xacro:property name="std_dev" value="0.05" />
<xacro:property name="mesh" value="slamtec_rplidar_ax.dae" />
<xacro:property name="collision">
<origin xyz="0.0 0.0 ${0.041/2.0}" rpy="0.0 0.0 0.0" />
<geometry>
<cylinder radius="${0.076/2.0}" length="0.041" />
</geometry>
</xacro:property>
<xacro:property name="inertial">
<origin xyz="0.0 0.0 ${0.041/2.0}" rpy="0.0 0.0 0.0" />
<mass value="0.190" />
<inertia ixx="0.000095206" ixy="0.0" ixz="0.0"
iyy="0.000095206" iyz="0.0"
izz="0.00013718" />
</xacro:property>
<xacro:property name="joint">
<origin xyz="0.0 0.0 0.031" rpy="0.0 0.0 ${pi}" />
</xacro:property>
</xacro:if>

<xacro:if value="${model == 'a2m8'}">
<xacro:property name="samples" value="800" />
<xacro:property name="dist_min" value="0.2" />
<xacro:property name="dist_max" value="10.0" />
<xacro:property name="dist_res" value="0.03" />
<xacro:property name="std_dev" value="0.05" />
<xacro:property name="mesh" value="slamtec_rplidar_a2m8.dae" />
<xacro:property name="collision">
<origin xyz="0.0 0.0 ${0.041/2.0}" rpy="0.0 0.0 0.0" />
<geometry>
<cylinder radius="${0.076/2.0}" length="0.041" />
</geometry>
</xacro:property>
<xacro:property name="inertial">
<origin xyz="0.0 0.0 ${0.041/2.0}" rpy="0.0 0.0 0.0" />
<mass value="0.190" />
<inertia ixx="0.000095206" ixy="0.0" ixz="0.0"
iyy="0.000095206" iyz="0.0"
izz="0.00013718" />
</xacro:property>
<xacro:property name="joint">
<origin xyz="0.0 0.0 0.031" rpy="0.0 0.0 ${pi}" />
</xacro:property>
</xacro:if>

<xacro:if value="${model == 'a2m7'}">
<xacro:property name="samples" value="1600" />
<xacro:property name="dist_min" value="0.2" />
<xacro:property name="dist_max" value="10.0" />
<xacro:property name="dist_res" value="0.03" />
<xacro:property name="std_dev" value="0.05" />
<xacro:property name="mesh" value="slamtec_rplidar_ax.dae" />
<xacro:property name="collision">
<origin xyz="0.0 0.0 ${0.041/2.0}" rpy="0.0 0.0 0.0" />
<geometry>
<cylinder radius="${0.076/2.0}" length="0.041" />
</geometry>
</xacro:property>
<xacro:property name="inertial">
<origin xyz="0.0 0.0 ${0.041/2.0}" rpy="0.0 0.0 0.0" />
<mass value="0.190" />
<inertia ixx="0.000095206" ixy="0.0" ixz="0.0"
iyy="0.000095206" iyz="0.0"
izz="0.00013718" />
</xacro:property>
<xacro:property name="joint">
<origin xyz="0.0 0.0 0.031" rpy="0.0 0.0 ${pi}" />
</xacro:property>
</xacro:if>

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

<link name="${prefix}slamtec_rplidar_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/${mesh}" />
</geometry>
</visual>

<collision>
<xacro:insert_block name="collision" />
</collision>

<inertial>
<xacro:insert_block name="inertial" />
</inertial>
</link>

<joint name="${prefix}slamtec_rplidar_to_${prefix}laser_joint" type="fixed">
<xacro:insert_block name="joint" />
<parent link="${prefix}slamtec_rplidar_link" />
<child link="${prefix}laser" />
</joint>

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

<gazebo reference="${prefix}laser">
<sensor type="gpu_lidar" name="${ns}${prefix}slamtec_rplidar_sensor">
<always_on>false</always_on>
<update_rate>10</update_rate>
<visualize>false</visualize>

<topic>${ns}${device_ns}scan</topic>
<ignition_frame_id>${ns}${prefix}laser</ignition_frame_id>

<ray>
<scan>
<horizontal>
<samples>${samples}</samples>
<resolution>1</resolution>
<min_angle>-${pi}</min_angle>
<max_angle>${pi}</max_angle>
</horizontal>
</scan>
<range>
<min>${dist_min}</min>
<max>${dist_max}</max>
<resolution>${dist_res}</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>${std_dev}</stddev>
</noise>
</ray>
</sensor>
</gazebo>

</xacro:macro>
</robot>
Loading

0 comments on commit 59f8172

Please sign in to comment.