Closed nigeno closed 1 year ago
Many thanks for reporting this error! The bug is fixed in https://github.com/SICKAG/sick_scan_xd/tree/feature/lrs3601_angle_settings and will be merged into the master in the next release. Please update to the new version.
@rostest Appreciate your prompt response! During test though I figured on line 773 it should be left as false:
772 basicParams[i].setScanAngleShift(0); 773 basicParams[i].setScanMirroredAndShifted(false);
In this case, it worked as expected.
In regards the changes for LRS 36x0, I don't have the actual scanner to test, so cannot confirm proper operation. It's got quite different angle coordinates:
Thanks again
@nigeno Thanks for your feedback! Your settings are indeed identical to the new ones in the branch. We checked the configuration and angle offsets for both LRS36x0 and LRS36x1.
@rostest Actually I had to change the 773 line from true to false to make it work. That's why I mentioned it. Unless I understood something wrongly..
Thanks for your feedback! We have tested the driver against LRS36x0 and LRS36x1 and made adjustments to the code. The branch https://github.com/SICKAG/sick_scan_xd/tree/feature/lrs3601_angle_settings is updated.
We used the following test cases:
Case 1: LRS36x0 upright (SICK logo on lidar unrotated).
Case 2: LRS36x0 upside down (SICK logo on lidar upside down). In this case, we compensated the upside down mounting by an additional rotation of 180° about the ROS-X axis. For upside down mounting we provided launchfiles sick_lrs_36x0_upside_down.launch and sick_lrs_36x1_upside_down.launch, which configures a roll angle of 180° (rotation about x axis) by <param name="add_transform_xyz_rpy" type="string" value="0,0,0,3.141592,0,0" />
Case 3: LRS36x1 upright (SICK logo on lidar unrotated)
Case 4: LRS36x1 upside down (SICK logo on Lidar upside down). In this case, we used sick_lrs_36x1_upside_down.launch to compensate the upside down mounting by a 180° rotation about the x axis.
We tested all four cases against a setup where a significant corner gives a good indication of the correct rotation of the pointcloud. We recommend to place an object at a clearly recognizable position in front of the wall, which is visible in the pointcloud at a certain angle. This way the position and angle of the object in the pointcloud can be verified. To visualize the pointcloud we recommend e.g. rviz using ROS or matplotlib in python.
The following rviz sceenshot shows the pointcloud in our test cases:
Solved due to bugfix.
I was testing LD-LRS3601 laser with the driver on native Windows and found an issue. I rechecked the issue with sick_scan_xd_api_test.cpp and it showed the same results.
The Cartesian point coordinates were printed out to the console using the following code:
`// Get cartesian point coordinates
int polar_point_offset = row_idx msg.row_step + col_idx msg.point_step; float point_x = ((float)(msg.data.buffer + polar_point_offset + field_offset_x)); float point_y = ((float)(msg.data.buffer + polar_point_offset + field_offset_y)); float point_z = ((float)(msg.data.buffer + polar_point_offset + field_offset_z)); printf("[Info]: x, y, z: %f x %f x %f \n", point_x, point_y, point_z); `
The data were compared to the Scan view in SOPAS Engineering Tool 2021.3.
The angle range used in the experiment is +135deg to +225deg and set in the sick_lrs_36x1.launch file like this:
`param name="min_ang" type="double" value="0.785398"/> <!-- default start angle for LRS 36x1: +135 deg incl. angle offset (45 deg excl. angle offset, angle offset = -90 deg)
param name="max_ang" type="double" value="2.356194"/> <!-- default stop angle for LRS 36x1: +225 deg incl. angle offset (135 deg excl. angle offset, angle offset = -90 deg)`
Here's the view from SOPAS:
Print out from the driver to the console:
`[Info]: apiTestCartesianPointCloudMsgCallback(apiHandle:000001A2B6A54CB0): 361x1 pointcloud callback...
[Info]: x, y, z: 7.447249 x 7.447249 x 0.000000 // 1st point ........................ [Info]: x, y, z: 0.000037 x 8.516001 x 0.000000 // middle point ........................ [Info]: x, y, z: -7.696083 x 7.696219 x 0.000000 // last point `
Now if you compare the results you can see the differences:
I've made it identical with the following conversion: x = - y_driver y = x_driver
Definitely a point can be made that the driver system coordinate is unique, more intuitive and shouldn't be compared to SOPAS view. Though, I believe it should follow the standard established in the official Siemens tool - SOPAS.
The reason why it can happen is because of the 90deg angle offset. It can be easily fixed in the driver code. Possibly it should be put to 0deg for LD-LRS3601 scanner. Don't know the reasoning to have it.