Closed Tecuma1 closed 2 years ago
Hi @Tecuma1 , unfortunately I don't have time at the moment to help with this issue. It looks like you are on the right track though!
Can you maybe point me in the right direction? I kept trying to change the sick_tim310_1130000m01_parser.cpp file and it runs with the adjusted values, but I still only receive 90 data points.
I also tried running the roslaunch sick_tim sick_tim310s01.launch file, this node seems the better fit for my sensor specification wise. I get the following warning:
[ WARN] [1649068130.075785916]: received less fields than expected fields (actual: 221, expected: 580), ignoring scan [ WARN] [1649068130.075976425]: are you using the correct node? (124 --> sick_tim310_1130000m01, 306 --> sick_tim551_2050001, 580 --> sick_tim310s01, 592 --> sick_tim310)
After changing the fields to the actual fields (221) I get the error:
[sick_tim310s01-2] process has died [pid 22070, exit code -11, cmd /home/odroid/ros_catkin_ws/devel/lib/sick_tim/sick_tim310s01 __name:=sick_tim310s01 __log:=/home/odroid/.ros/log/43ec6b12-b3ec-11ec-9148-001e06430728/sick_tim310s01-2.log]. log file: /home/odroid/.ros/log/43ec6b12-b3ec-11ec-9148-001e06430728/sick_tim310s01-2*.log
I think the actual fields received are the measurements right? That would be weird because a 1 degree angular sensor with a 270 degree range would mean that you would need at least 270 fields (instead of the 221 received). In the SOPAS engineering tool I again see the 1 degree angular resolution specification, so I think it should be possible.
Any ideas?
Kind regards,
Arne
I think the actual fields received are the measurements right? That would be weird because a 1 degree angular sensor with a 270 degree range would mean that you would need at least 270 fields (instead of the 221 received). In the SOPAS engineering tool I again see the 1 degree angular resolution specification, so I think it should be possible.
Yep, for a 270° laser scanner at 1° resolution you would need at least 271 fields (or twice that if the scanner also outputs intensities), plus a couple for the header and footer. What you're seeing (and what the Technical Information (see below) says) is consistent with a scanner that outputs distances at 3° resolution and also outputs intensities. I don't think it can be configured differently, but you can contact SICK and ask directly.
Here's a little tutorial on how to adjust the parser to your scanner:
The first step is to set the publish_datagram
parameter to true
, record a short (10 second) rosbag of the datagram
topic and upload it here. That way we can have a look at it.
Once you have the rosbag of the datagrams, you can use rostopic echo
to see the actual datagrams. Compare with the specification of the format and modify the parser (see below) until it matches.
Here is the documentation of the datagram format for your scanner: https://cdn.sick.com/media/docs/5/35/135/technical_information_tim51x_messender_laserscanner_en_im0053135.pdf (TIM510-9950000S01 product page -> Downloads -> Technical Information). The Part number of that document is 8016425. The interesting part starts on page 21 (section 5.3 "Format for output of measured values").
According to the specification, there are:
So in total, that's 216 fields. I don't know why the actual datagrams seem to have 221 fields. I think the parser counts the <STX>
and <ETX>
bytes at the beginning and end as well; still there's 3 extra bytes, so my list above is not correct. This is where you have to look at the datagrams and try to parse it "by hand" to figure out the exact indices of all the fields and correct my list.
The next step is to modify the parser to match the specification.
The datagram format that the parser currently expects is documented in the sick_tim310_1130000m01_parser.cpp
comments (search for <STX>
, that's where it starts; the comments for the field numbers after 26 were copied from a different parser and are not correct, look at the numbers in the code instead). Sick likes to change it around for every scanner, but it's always the same pattern. There are a couple of header fields (here: fields 0..25), then the actual measurements (here: fields 26..115), then for those scanners that support intensities some more metadata fields and one field per intensity measurement (same length as distance measurements), then some footers.
Thanks!
I found the mistake in the document you referenced:
Here is the documentation of the datagram format for your scanner: https://cdn.sick.com/media/docs/5/35/135/technical_information_tim51x_messender_laserscanner_en_im0053135.pdf (TIM510-9950000S01 product page -> Downloads -> Technical Information). The Part number of that document is 8016425. The interesting part starts on page 21 (section 5.3 "Format for output of measured values").
I knew it was something simple as a switch. In the SOPAS engineering tool I needed to set the baud rate to 460,800 bit/s instead of the standard 115,200 bit/s (chapter 2.3 of the document). Now I receive 581 fields with RSSI on.
According to the datasheet the data points indeed start at the field index 27. Also the data looks correct. I also uncommended the intensity lines and it seems to be working. But the standard index for this sensor starts at 304. Is this correct? Because the index 27+271 = 298. Maybe I am missing some fields.
Conclusion for further users:
Thank you for your help!
Kind regards,
Arne
Wow, great find!
581 fields sounds suspiciously close to 580, which is what the sick_tim310s01
node uses. If you have set a name for your scanner, and that name contains a space, then this would raise the number of fields from 580 to 581. Perhaps the sick_tim310s01
node works for you without modifications.
I think the sick_tim310_1130000m01.launch works now. The sick_tim310s01 node gives me the warning: [ WARN] [1649162699.321706141]: ROS time is 0! Did you set the parameter use_sim_time to true?
Also I can't visualize the data in rviz, but I can access the data with my own program and it works. Difference between the 2 nodes are that the sick_tim310s01 uses 1 lower index for the fields. And I think I didn't gave it a name. In SOPAS you can check a checkbox for outputting the name and it was still unchecked.
I think the sick_tim310_1130000m01.launch works now. The sick_tim310s01 node gives me the warning: [ WARN] [1649162699.321706141]: ROS time is 0! Did you set the parameter use_sim_time to true?
Also I can't visualize the data in rviz, but I can access the data with my own program and it works. Difference between the 2 nodes are that the sick_tim310s01 uses 1 lower index for the fields. And I think I didn't gave it a name. In SOPAS you can check a checkbox for outputting the name and it was still unchecked.
Correction:
I had to restart roscore.. Now it runs without problems and I can visualize data in rviz. The TiM TIM510-9950000S01 runs on sick_tim310s01 node using 1 degree angular resolution without changes. The TiM TIM510-9950000S01 runs on sick_tim310_1130000m01 using 3 degree angular resolution without changes.
Thanks for the help! Maybe add this sensor in the list?
Kind regards,
Arne
Yup, I've updated the wiki page.
In case somebody later stumbles over this issue: you have to set the data rate to 460,800 bit/s! (Clarifying this because you wrote 115,200 bit/s, which is wrong).
One more question: You are running the scanner over a serial connection, right?
I am just using the usb connection using the micro usb port. Apparently the baud rate setting also changed the setting for the usb connection.
Alright, thanks!
Hi there!
I got the sensor working with the sick_tim310_1130000m01 launch file. My sensor (TIM510-9950000S01) has a 1 degree angular resolution, while the sick_tim310_1130000m01 has a 3 degree angular resolution. I've tried to change the package by adjusting the sick_tim310_1130000m01_parser.cpp file. I changed the following 3 rules:
This doesn't seem to work. Can I adjust this package for a 1 degree angular resolution?
Thank you in advance!
Kind regards,
Arne