velodyne
velodyne copied to clipboard
Using 2 velodynes, receiving mixed messages in separated topics from both velodynes
- OS and Version: Ubuntu 18.04
- ROS Version: Melodic
- Built from Source or Downloaded from Official Repository: Built from source
- Version: Commit 75c7c68 I'm trying to receive messages from two velodynes and then merge the scans for using the data with AMCL package. I've modified the launcher so the velodyne's scan topic is ${arg frame_id}_scan instead of just scan and I've realized that I'm receiving in each velodyne's topic mixed messages from both velodynes instead of the ones corresponding to the velodyne of the topic. Does anyone had this problem and can tell me how to solve it? Thank you in advance.
Modified launcher:
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for a VLP-16 -->
<launch>
<!-- declare arguments with default values -->
<arg name="calibration" default="$(find velodyne_pointcloud)/params/VLP16db.yaml"/>
<arg name="device_ip" default="" />
<arg name="frame_id" default="velodyne" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.4" />
<arg name="pcap" default="" />
<arg name="port" default="2368" />
<arg name="read_fast" default="false" />
<arg name="read_once" default="false" />
<arg name="repeat_delay" default="0.0" />
<arg name="rpm" default="600.0" />
<arg name="gps_time" default="false" />
<arg name="cut_angle" default="-0.01" />
<arg name="timestamp_first_packet" default="false" />
<arg name="laserscan_ring" default="-1" />
<arg name="laserscan_resolution" default="0.007" />
<arg name="organize_cloud" default="false" />
<!--
0 degrees >>>> 0.0 rad >>>> FRONTAL
180 degrees >>>> 3.14159265359 rad >>>> REAR
-->
<arg name="view_direction" default="0.0" /><!--[0-2*pi]center of view angle in radians in the device frame of reference.-->
<!--
240 degrees >>>> 4.18879000000 rad
220 degrees >>>> 3.83972000000 rad
200 degrees >>>> 3.49066000000 rad
180 degrees >>>> 3.14159265359 rad
160 degrees >>>> 2.79252680319 rad
140 degrees >>>> 2.44346095279 rad
120 degrees >>>> 2.09439510239 rad
-->
<arg name="view_width" default="3.83972000000" /><!--[0-2*pi]Width of view angle in radians in the XY plane of the device frame of reference-->
<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="device_ip" value="$(arg device_ip)"/>
<arg name="frame_id" value="$(arg frame_id)"/>
<arg name="manager" value="$(arg manager)" />
<arg name="model" value="VLP16"/>
<arg name="pcap" value="$(arg pcap)"/>
<arg name="port" value="$(arg port)"/>
<arg name="read_fast" value="$(arg read_fast)"/>
<arg name="read_once" value="$(arg read_once)"/>
<arg name="repeat_delay" value="$(arg repeat_delay)"/>
<arg name="rpm" value="$(arg rpm)"/>
<arg name="gps_time" value="$(arg gps_time)"/>
<arg name="cut_angle" value="$(arg cut_angle)"/>
<arg name="timestamp_first_packet" value="$(arg timestamp_first_packet)"/>
</include>
<!-- start cloud nodelet -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="model" value="VLP16"/>
<arg name="calibration" value="$(arg calibration)"/>
<arg name="manager" value="$(arg manager)" />
<arg name="fixed_frame" value="$(arg frame_id)" />
<arg name="target_frame" value="$(arg frame_id)" />
<arg name="max_range" value="$(arg max_range)"/>
<arg name="min_range" value="$(arg min_range)"/>
<arg name="organize_cloud" value="$(arg organize_cloud)"/>
<arg name="view_width" value="$(arg view_width)"/>
<arg name="view_direction" value="$(arg view_direction)"/>
</include>
<!-- start laserscan nodelet -->
<include file="$(find velodyne_pointcloud)/launch/laserscan_nodelet.launch">
<arg name="manager" value="$(arg manager)" />
<arg name="ring" value="$(arg laserscan_ring)"/>
<arg name="resolution" value="$(arg laserscan_resolution)"/>
</include>
</launch>
Launch script:
# Local variables for script purposes
NOT_FOUND=true
ALL_OK=false
NUM_LIDARS=0
# All velodyne data are stored in an array called LIDAR
declare -A LIDAR
if [ -z $CAR_TYPE ]; then
echo "CAR_TYPE variable not set. Try adding to ~/.bashrc the following command: export CAR_TYPE=cas (cas/c4/golf)\n"
exit 1
else
if [ $CAR_TYPE = "cas" ]; then
echo "CAR_TYPE selected is cas"
# The data of the velodyne in the front of the CAS is stored in FRONT
declare -A FRONT
# The data of the velodyne in the back of the CAS is stored in BACK
declare -A BACK
# FRONT velodyne data
FRONT["IP"]=192.168.1.91
FRONT["FRAME_ID"]=front_velodyne
FRONT["PORT"]=2368
FRONT["RPM"]=1200.0
FRONT["RING"]=12
FRONT["VIEW_DIRECTION"]=0.0
FRONT["VIEW_WIDTH"]=3.14159265359
FRONT["PING"]=false
FRONT["COUNT"]=0
# BACK velodyne data
BACK["IP"]=192.168.1.201
BACK["FRAME_ID"]=back_velodyne
BACK["PORT"]=2368
BACK["RPM"]=1200.0
BACK["RING"]=12
BACK["VIEW_DIRECTION"]=1,57079632679
BACK["VIEW_WIDTH"]=3.14159265359
BACK["PING"]=false
BACK["COUNT"]=0
# FRONT and BACK are stored in LIDAR
i=1
for key in "${!FRONT[@]}"; do
LIDAR[$i,$key]=${FRONT[$key]}
done
((i++))
for key in "${!BACK[@]}"; do
LIDAR[$i,$key]=${BACK[$key]}
done
declare -p LIDAR
NUM_LIDARS=2
fi
if [ $CAR_TYPE = "c4" ]; then
echo "CAR_TYPE selected is c4"
# The data of the velodyne is stored in FRONT
declare -A FRONT
# FRONT velodyne data
FRONT["IP"]=192.168.1.201
FRONT["FRAME_ID"]=velodyne
FRONT["PORT"]=2369
FRONT["RPM"]=1200.0
FRONT["RING"]=7
FRONT["VIEW_DIRECTION"]=0.0
FRONT["PING"]=false
FRONT["COUNT"]=0
FRONT["VIEW_WIDTH"]=6,28318530718
# FRONT is stored in LIDAR
i=1
for key in "${!FRONT[@]}"; do
LIDAR[$i,$key]=${FRONT[$key]}
done
declare -p LIDAR
NUM_LIDARS=1
fi
fi
if [ -z $TEST_WITH_PCAP ]; then
echo "No PCAP file detected. Trying to connect to VLP16 sensors"
until $ALL_OK; do
i=1
while [ $i -le $NUM_LIDARS ]; do
ALL_OK=true
if [ !${LIDAR[$i, PING]} ]; then
ping -q -c3 "${LIDAR[$i,IP]}" > /dev/null
if [ $? -eq 0 ]; then
echo "Succeded to ping VLP16 ${LIDAR[$i,IP]}\nLaunching Driver...\n"
roslaunch velodyne_pointcloud VLP16_points.launch device_ip:=${LIDAR[$i,IP]} frame_id:=${LIDAR[$i,FRAME_ID]} port:=${LIDAR[$i,PORT]} rpm:=${LIDAR[$i,RPM]} laserscan_ring:=${LIDAR[$i,RING]} view_direction:=${LIDAR[$i,VIEW_DIRECTION]} view_width:=${LIDAR[$i,VIEW_WIDTH]} &
LIDAR[$i,PING]=true
LIDAR[$i,COUNT]=0
sleep 2s
else
echo "No ping from VLP16 (${LIDAR[$i,IP]})"
if [ $( ifconfig | grep addr:192.168.1.14| wc -l) -lt 1 ]; then
printf "Not connected to velodyne network\n"
fi
LIDAR[$i,COUNT]=$((LIDAR[$i,COUNT]+1))
printf "Ping not established, attempt number: ${LIDAR[$i,COUNT]} \n"
ALL_OK=false
fi
fi
((i++))
done
done
else
echo "Using file: $TEST_WITH_PCAP"
i=1
while [ $i -le $NUM_LIDARS ]; do
echo "Launching driver for VLP16 (${LIDAR[$i,IP]})"
roslaunch velodyne_pointcloud VLP16_points.launch device_ip:=${LIDAR[$i,IP]} frame_id:=${LIDAR[$i,FRAME_ID]} port:=${LIDAR[$i,PORT]} pcap:=${EST_WITH_PCAP} rpm:=${LIDAR[$i,RPM]} laserscan_ring:=${LIDAR[$i,RING]} view_direction:=${LIDAR[$i,VIEW_DIRECTION]} view_width:=${LIDAR[$i,VIEW_WIDTH]} &
((i++))
sleep 2s
done
fi
exit 0
You should, instead, launch each driver in its own namespace (e.g. /lidar1/velodyne_driver
, /lidar2/velodyne_driver
) and then you'll need to combine the two scans into one using a fusion node. An example of one can be found in Autoware.Auto.
Make sure you define different ports for each sensor. Currently it looks like both are using 2368. So set one of them to 2369 (or some other unused port).