Skip to content

Commit

Permalink
Added rplidars s2 and s3 (#35)
Browse files Browse the repository at this point in the history
* Added rplidars s2 and s3

Signed-off-by: Jakub Delicat <[email protected]>

* small fixes

---------

Signed-off-by: Jakub Delicat <[email protected]>
Co-authored-by: rafal-gorecki <[email protected]>
  • Loading branch information
delihus and rafal-gorecki authored Nov 28, 2023
1 parent 1b91ab8 commit 8b934bc
Show file tree
Hide file tree
Showing 7 changed files with 498 additions and 4 deletions.
92 changes: 92 additions & 0 deletions meshes/slamtec_rplidar_s2.dae

Large diffs are not rendered by default.

92 changes: 92 additions & 0 deletions meshes/slamtec_rplidar_s3.dae

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion urdf/slamtec_rplidar_a2.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
<stddev>0.03</stddev>
</noise>
</ray>

Expand Down
4 changes: 2 additions & 2 deletions urdf/slamtec_rplidar_a3.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -130,13 +130,13 @@
<range>
<min>0.2</min>
<!-- as an tradeoff between white and black object range -->
<max>16.0</max>
<max>20.0</max>
<resolution>0.05</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
<stddev>0.03</stddev>
</noise>
</ray>

Expand Down
2 changes: 1 addition & 1 deletion urdf/slamtec_rplidar_s1.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
<stddev>0.03</stddev>
</noise>
</ray>

Expand Down
155 changes: 155 additions & 0 deletions urdf/slamtec_rplidar_s2.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="slamtec_rplidar_s2"
params="parent_link xyz rpy
use_gpu:=false
tf_prefix:=None
topic:=scan
frame_id:=laser
simulation_engine:=gazebo-classic">

<xacro:if value="${use_gpu}">
<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<xacro:property name="ray_type" value="gpu_ray" />
</xacro:if>
<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<xacro:property name="ray_type" value="gpu_lidar" />
</xacro:if>
</xacro:if>
<xacro:unless value="${use_gpu}">
<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<xacro:property name="ray_type" value="ray" />
</xacro:if>
<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<!-- use_gpu has to be set to true, CPU lidar doesn't work in ignition -
https://github.com/gazebosim/gz-sensors/issues/26 -->
<xacro:property name="ray_type" value="lidar" />
</xacro:if>
</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>

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

<link name="${prefix}slamtec_rplidar_s2_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<geometry>
<mesh filename="file://$(find ros_components_description)/meshes/slamtec_rplidar_s2.dae" />
</geometry>
</visual>

<!-- base and head collision -->
<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>
</collision>

<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" />
</inertial>
</link>

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

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

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

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

<update_rate>10.0</update_rate>
<ray>
<scan>
<horizontal>
<samples>3000</samples>
<resolution>1</resolution>
<min_angle>-${pi}</min_angle>
<max_angle>${pi}</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>30.0</max>
<resolution>0.03</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>
<always_on>1</always_on>
<visualize>false</visualize>
</sensor>
</gazebo>
<gazebo>
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
</gazebo>
</xacro:if>

<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<gazebo reference="${prefix}${frame_id}">
<sensor type="${ray_type}" name="${prefix}slamtec_rplidar_s2_sensor">
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>3000</samples>
<resolution>1</resolution>
<min_angle>-${pi}</min_angle>
<max_angle>${pi}</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>30.0</max>
<resolution>0.013</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.03</stddev>
</noise>
</ray>

<update_rate>10.0</update_rate>

<plugin name="scan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace></namespace>
<remapping>~/out:=${topic}</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>${prefix}${frame_id}</frame_name>
</plugin>
</sensor>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>
155 changes: 155 additions & 0 deletions urdf/slamtec_rplidar_s3.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="slamtec_rplidar_s3"
params="parent_link xyz rpy
use_gpu:=false
tf_prefix:=None
topic:=scan
frame_id:=laser
simulation_engine:=gazebo-classic">

<xacro:if value="${use_gpu}">
<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<xacro:property name="ray_type" value="gpu_ray" />
</xacro:if>
<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<xacro:property name="ray_type" value="gpu_lidar" />
</xacro:if>
</xacro:if>
<xacro:unless value="${use_gpu}">
<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<xacro:property name="ray_type" value="ray" />
</xacro:if>
<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<!-- use_gpu has to be set to true, CPU lidar doesn't work in ignition -
https://github.com/gazebosim/gz-sensors/issues/26 -->
<xacro:property name="ray_type" value="lidar" />
</xacro:if>
</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>

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

<link name="${prefix}slamtec_rplidar_s3_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<geometry>
<mesh filename="file://$(find ros_components_description)/meshes/slamtec_rplidar_s3.dae" />
</geometry>
</visual>

<!-- base and head collision -->
<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>
</collision>

<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" />
</inertial>
</link>

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

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

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

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

<update_rate>10.0</update_rate>
<ray>
<scan>
<horizontal>
<samples>3000</samples>
<resolution>1</resolution>
<min_angle>-${pi}</min_angle>
<max_angle>${pi}</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>40.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.03</stddev>
</noise>
</ray>
<always_on>1</always_on>
<visualize>false</visualize>
</sensor>
</gazebo>
<gazebo>
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
</gazebo>
</xacro:if>

<xacro:if value="${simulation_engine == 'gazebo-classic'}">
<gazebo reference="${prefix}${frame_id}">
<sensor type="${ray_type}" name="${prefix}slamtec_rplidar_s3_sensor">
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>3200</samples>
<resolution>1</resolution>
<min_angle>-${pi}</min_angle>
<max_angle>${pi}</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>40.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>

<update_rate>10.0</update_rate>

<plugin name="scan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace></namespace>
<remapping>~/out:=${topic}</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>${prefix}${frame_id}</frame_name>
</plugin>
</sensor>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>

0 comments on commit 8b934bc

Please sign in to comment.