You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
# Optional range filter configuration: If the range of a scan point is less than range_min or greater than range_max, the point can be filtered.
12
+
# Depending on parameter range_filter_handling, the following filter can be applied for points with a range not within [range_min, range_max],
13
+
# see enumeration RangeFilterResultHandling in range_filter.h:
14
+
# 0: RANGE_FILTER_DEACTIVATED, do not apply range filter (default)
15
+
# 1: RANGE_FILTER_DROP, drop point, if range is not within [range_min, range_max]
16
+
# 2: RANGE_FILTER_TO_ZERO, set range to 0, if range is not within [range_min, range_max]
17
+
# 3: RANGE_FILTER_TO_RANGE_MAX, set range to range_max, if range is not within [range_min, range_max]
18
+
# 4: RANGE_FILTER_TO_FLT_MAX, set range to FLT_MAX, if range is not within [range_min, range_max]
19
+
# 5: RANGE_FILTER_TO_NAN set range to NAN, if range is not within [range_min, range_max]
20
+
# Note: Range filter applies only to Pointcloud messages, not to LaserScan messages.
21
+
# Using range_filter_handling 4 or 5 requires handling of FLT_MAX and NAN values in an application.
22
+
range_min: 0.05
23
+
range_max: 25.0
24
+
range_filter_handling: 0
25
+
26
+
hostname: 192.168.0.1
27
+
cloud_topic: cloud
28
+
port: 2112
29
+
timelimit: 5
30
+
sw_pll_only_publish: true
31
+
use_generation_timestamp: true # Use the lidar generation timestamp (true, default) or send timestamp (false) for the software pll converted message timestamp
32
+
start_services: true # start ros service for cola commands
33
+
activate_lferec: true # activate field monitoring by lferec messages
34
+
activate_lidoutputstate: true # activate field monitoring by lidoutputstate messages
35
+
activate_lidinputstate: true # activate field monitoring by lidinputstate messages
36
+
min_intensity: 0.0# Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0)
37
+
38
+
ang_res: 0.5# Supported values are "0.25" and "0.50"
39
+
scan_freq: 50# Supported values are "25" and "50"
40
+
# Note: angular resolution and scanning frequency of a LMS111 can be configured by parameter "ang_res" (values "0.25" or "0.5") and "scan_freq" (values "25" or "50")
41
+
# After setting "ang_res" and "scan_freq", it takes ca. 30 seconds until the pointcloud is published.
42
+
# Recommendation: It is recommended to specify the desired angular resolution and scan rate in this launch file.
43
+
# In this case, it is necessary to wait approx. 30 sec. until the Lidar changes to status "OK".
44
+
# Alternatively, these settings can be configured in SOPAS-ET, transferred to the EEProm of the lidar and
45
+
# then permanently stored. In this case, the explicit specification of scan rate and angular resolution
46
+
# can be omitted and the waiting time can be avoided.
47
+
48
+
# Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform)
49
+
# Note: add_transform_xyz_rpy is specified by 6D pose x, y, z, roll, pitch, yaw in [m] resp. [rad]
50
+
# It transforms a 3D point in cloud coordinates to 3D point in user defined world coordinates:
51
+
# add_transform_xyz_rpy := T[world,cloud] with parent "world" and child "cloud", i.e. P_world = T[world,cloud] * P_cloud
52
+
# The additional transform applies to cartesian lidar pointclouds and visualization marker (fields)
53
+
# It is NOT applied to polar pointclouds, radarscans, ldmrs objects or other messages
54
+
add_transform_xyz_rpy: "0,0,0,0,0,0"
55
+
add_transform_check_dynamic_updates: false
56
+
57
+
message_monitoring_enabled: true # Enable message monitoring with reconnect+reinit in case of timeouts, default: true
read_timeout_millisec_startup: 120000# 120 sec read timeout during startup (sensor may be starting up, which can take up to 120 sec.), default: 120000 milliseconds
60
+
read_timeout_millisec_kill_node: 150000# 150 sec pointcloud timeout, ros node will be killed if no point cloud published within the last 150 sec., default: 150000 milliseconds
61
+
client_authorization_pw: F4724744# Default password for client authorization
62
+
63
+
# Configuration of ROS quality of service:
64
+
# On ROS-1, parameter "ros_qos" sets the queue_size of ros publisher
65
+
# On ROS-2, parameter "ros_qos" sets the QoS of ros publisher to one of the following predefined values:
0 commit comments