Add the ability to control the depth and reliability of the /scan topic

This commit is contained in:
2026-04-23 08:46:15 +00:00
parent 0174cb599f
commit c7b1d60859
5 changed files with 62 additions and 8 deletions
+2 -1
View File
@@ -70,7 +70,8 @@ git remote add sllidar_ros2 https://github.com/m5p3nc3r/sllidar_ros2.git
| File | Change |
|---|---|
| `src/sllidar_node.cpp` | `/scan` publisher QoS set to `BEST_EFFORT` with depth 2. Required for compatibility with Nav2 and RViz2, which subscribe to `/scan` with `BEST_EFFORT`. The upstream default (`RELIABLE`) causes those consumers to receive no data. |
| `src/sllidar_node.cpp` | `/scan` publisher QoS made configurable via `scan_qos_depth` (int) and `scan_qos_reliability` (`best_effort`\|`reliable`) parameters. Defaults to `best_effort`, depth 2 — required for Nav2 / RViz2 compatibility. |
| `launch/sllidar_a1_launch.py` | Exposes `scan_qos_depth` and `scan_qos_reliability` as launch arguments. |
The upstream Slamtec repository is at:
+18 -5
View File
@@ -18,6 +18,8 @@ def generate_launch_description():
inverted = LaunchConfiguration('inverted', default='false')
angle_compensate = LaunchConfiguration('angle_compensate', default='true')
scan_mode = LaunchConfiguration('scan_mode', default='Sensitivity')
scan_qos_depth = LaunchConfiguration('scan_qos_depth', default='10')
scan_qos_reliability = LaunchConfiguration('scan_qos_reliability', default='reliable')
return LaunchDescription([
@@ -55,17 +57,28 @@ def generate_launch_description():
default_value=scan_mode,
description='Specifying scan mode of lidar'),
DeclareLaunchArgument(
'scan_qos_depth',
default_value=scan_qos_depth,
description='Queue depth for the /scan publisher'),
DeclareLaunchArgument(
'scan_qos_reliability',
default_value=scan_qos_reliability,
description='Reliability policy for the /scan publisher: best_effort or reliable'),
Node(
package='sllidar_ros2',
executable='sllidar_node',
name='sllidar_node',
parameters=[{'channel_type':channel_type,
'serial_port': serial_port,
'serial_baudrate': serial_baudrate,
parameters=[{'channel_type': channel_type,
'serial_port': serial_port,
'serial_baudrate': serial_baudrate,
'frame_id': frame_id,
'inverted': inverted,
'angle_compensate': angle_compensate}],
'inverted': inverted,
'angle_compensate': angle_compensate,
'scan_qos_depth': scan_qos_depth,
'scan_qos_reliability': scan_qos_reliability}],
output='screen'),
])
+17 -2
View File
@@ -58,9 +58,24 @@ class SLlidarNode : public rclcpp::Node
SLlidarNode()
: Node("sllidar_node")
{
// QoS parameters must be declared here because the publisher is created
// before init_param() is called in work_loop().
this->declare_parameter<int>("scan_qos_depth", 2);
this->declare_parameter<std::string>("scan_qos_reliability", "best_effort");
scan_pub = this->create_publisher<sensor_msgs::msg::LaserScan>("scan", rclcpp::QoS(rclcpp::KeepLast(2)).best_effort());
int qos_depth;
std::string qos_reliability;
this->get_parameter_or<int>("scan_qos_depth", qos_depth, 2);
this->get_parameter_or<std::string>("scan_qos_reliability", qos_reliability, "best_effort");
auto qos = rclcpp::QoS(rclcpp::KeepLast(qos_depth));
if (qos_reliability == "best_effort") {
qos.best_effort();
} else {
qos.reliable();
}
scan_pub = this->create_publisher<sensor_msgs::msg::LaserScan>("scan", qos);
}
private: