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
Hi! Thanks for your work. I'm trying to integrate two PicoScan 150 LiDARs in our project. I need to receive the point cloud published by the devices, which I am able to do by modifying the test/src/sick_scan_xd_api/sick_scan_xd_api_test.cpp example program.
To run multiple lidars simultaneously, we recommend using ROS or running sick_scan_xd in multiple and separate processes, so that each process serves one sensor.
both the node name, the ip-address of the sensor and the pointcloud topic have to be configured differently for each node.
Node name, ip-address and pointcloud topic can be configured in the launch-file or by commandline argument:
I do that by duplicating the launch/sick_picoscan.launch file into sick_picoscan_1.launch and sick_picoscan_2.launch, in which I simply changed every topic name so to append a suffix _1 or _2.
Then I launch the programs with a bash script, in the end the actual program being called is like
where <LiDAR_IP> and <PC_IP> are the correct ones. The first program runs fine, and I can see some debug prints in the registered callback function, even with the correctly changed topic name. But the second program can't start, (of course I changed the suffixes from _1 to _2) and instead I get this output:
My guess is that I need to specify a different port, as shown in the test/scripts/run_linux_ros2_simu_tim7xx_twin.bash example linked in the FAQ? Note however that the launch file arguments are slightly different, for instance the topic and port arguments have different names (and for the port ones I can't figure out which ones should I use). Thanks!
The text was updated successfully, but these errors were encountered:
Thanks for your feedback. You are right, both the ip addresses and the udp port numbers must be different for each picoScan lidar. Please use SOPAS Air to set individual ip addresses (e.g. 192.168.0.1 and 192.168.0.2), different udp ports (e.g. 2115 and 2116) and different imu udp ports (e.g. 7503 and 7504) on both lidars. Use these settings in the launch files, e.g.:
sick_picoscan_1.launch:
<param name="udp_port" type="int" value="2115" /> <!-- default udp port for picoScan150 resp. picoScan150 emulator is 2115 -->
<param name="imu_udp_port" type="int" value="7503"/> <!-- udp port for multiScan imu data (if imu_enable is true) -->
sick_picoscan_2.launch:
<param name="udp_port" type="int" value="2116" /> <!-- default udp port for picoScan150 resp. picoScan150 emulator is 2115 -->
<param name="imu_udp_port" type="int" value="7504"/> <!-- udp port for multiScan imu data (if imu_enable is true) -->
Then call single_lidar_listener /opt/sick/sick_picoscan_1.launch nodename:=sick_picoscan_1 hostname:=<LiDAR_1_IP> udp_receiver_ip:=<PC_IP> and single_lidar_listener /opt/sick/sick_picoscan_2.launch nodename:=sick_picoscan_2 hostname:=<LiDAR_2_IP> udp_receiver_ip:=<PC_IP>
We will add a note about different udp ports in the faq.
Hi! Thanks for your work. I'm trying to integrate two PicoScan 150 LiDARs in our project. I need to receive the point cloud published by the devices, which I am able to do by modifying the
test/src/sick_scan_xd_api/sick_scan_xd_api_test.cpp
example program.In the API documentation it's said
and in the FAQ
I do that by duplicating the
launch/sick_picoscan.launch
file intosick_picoscan_1.launch
andsick_picoscan_2.launch
, in which I simply changed every topic name so to append a suffix_1
or_2
.Then I launch the programs with a bash script, in the end the actual program being called is like
where
<LiDAR_IP>
and<PC_IP>
are the correct ones. The first program runs fine, and I can see some debug prints in the registered callback function, even with the correctly changed topic name. But the second program can't start, (of course I changed the suffixes from_1
to_2
) and instead I get this output:So, how can I run concurrently the two programs?
My guess is that I need to specify a different port, as shown in the
test/scripts/run_linux_ros2_simu_tim7xx_twin.bash
example linked in the FAQ? Note however that the launch file arguments are slightly different, for instance the topic and port arguments have different names (and for the port ones I can't figure out which ones should I use). Thanks!The text was updated successfully, but these errors were encountered: