Skip to content

Commit

Permalink
feat: change pointcloud concatenation timeout setting for each lidar …
Browse files Browse the repository at this point in the history
…sensors in xx1 laucher (#134)

* change lidar sync timeout settings

Signed-off-by: yoshiri <[email protected]>

* ci(pre-commit): autofix

* fix input offset size to fit with input topic num

Signed-off-by: yoshiri <[email protected]>

* ci(pre-commit): autofix

* use left/right lidar

Signed-off-by: yoshiri <[email protected]>

* ci(pre-commit): autofix

---------

Signed-off-by: yoshiri <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
YoshiRi and pre-commit-ci[bot] authored Apr 28, 2023
1 parent 75082b6 commit 4a50e4f
Showing 1 changed file with 9 additions and 2 deletions.
11 changes: 9 additions & 2 deletions aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,18 @@ def launch_setup(context, *args, **kwargs):
{
"input_topics": [
"/sensing/lidar/top/outlier_filtered/pointcloud",
# "/sensing/lidar/left/outlier_filtered/pointcloud",
# "/sensing/lidar/right/outlier_filtered/pointcloud",
"/sensing/lidar/left/outlier_filtered/pointcloud",
"/sensing/lidar/right/outlier_filtered/pointcloud",
"/sensing/lidar/rear/outlier_filtered/pointcloud",
],
"output_frame": LaunchConfiguration("base_frame"),
"input_offset": [
0.055,
0.025,
0.025,
0.025,
], # each sensor will wait 20, 50, 50, 50ms
"timeout_sec": 0.075, # set shorter than 100ms
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
Expand Down

0 comments on commit 4a50e4f

Please sign in to comment.