-
Notifications
You must be signed in to change notification settings - Fork 90
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
TiM TIM510-9950000S01 #97
Comments
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 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 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]. 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 |
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 Once you have the rosbag of the datagrams, you can use 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 The next step is to modify the parser to match the specification. The datagram format that the parser currently expects is documented in the |
Thanks! I found the mistake in the document you referenced:
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 |
I think the sick_tim310_1130000m01.launch works now. Also I can't visualize the data in rviz, but I can access the data with my own program and it works. |
Correction: I had to restart roscore.. 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. |
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
The text was updated successfully, but these errors were encountered: