Add the ability to control the depth and reliability of the /scan topic
This commit is contained in:
@@ -40,4 +40,6 @@ services:
|
||||
- frame_id:=${LIDAR_FRAME_ID:-laser}
|
||||
- serial_baudrate:=115200
|
||||
- angle_compensate:=true
|
||||
- scan_qos_depth:=${LIDAR_QOS_DEPTH:-2}
|
||||
- scan_qos_reliability:=${LIDAR_QOS_RELIABILITY:-best_effort}
|
||||
restart: unless-stopped
|
||||
|
||||
+2
-1
@@ -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,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'),
|
||||
])
|
||||
|
||||
|
||||
@@ -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:
|
||||
|
||||
@@ -0,0 +1,23 @@
|
||||
# Troubleshooting
|
||||
|
||||
## No sensor data is received on topic
|
||||
|
||||
Data is sent over UDP, and if the sensor data exceeds the maximum receive buffer size of the network stack, the data frame will be silently discarded.
|
||||
|
||||
The solution is to increase the receive memory buffer size
|
||||
|
||||
```bash
|
||||
sudo sysctl -w net.core.rmem_max=2097152
|
||||
sudo sysctl -w net.core.rmem_default=2097152
|
||||
```
|
||||
|
||||
## Discarding message because the queue is full
|
||||
|
||||
If you are getting a message like:
|
||||
```
|
||||
[rviz]: Message Filter dropping message: frame 'laser' at time 1776876114.823 for reason 'discarding message because the queue is full'
|
||||
```
|
||||
|
||||
This could be because there is no `/tf` topic available. This topic is used to describe the relationship between coordinate systems (robot position, lidar position, camera position etc).
|
||||
|
||||
If this is the case, you can changet the fixed frame reference to the lidar itself. Change the `Global Options -> Fixed Frame` option from `map` to `laser` to tell the system to use the laser as the base of all transforms.
|
||||
Reference in New Issue
Block a user