Closed ogamache closed 2 years ago
Can you copy-paste the specific error?
Just an additional check, is your pointcloud of the type sensor_msgs/PointCloud2
? You can also double check that it's publishing a ring field. E.g. for velodyne vlp-16 I would type where /velodyne/front/points is the lidar topic: rostopic echo /velodyne/front/points/fields
Looks like this for me:
-
name: "x"
offset: 0
datatype: 7
count: 1
-
name: "y"
offset: 4
datatype: 7
count: 1
-
name: "z"
offset: 8
datatype: 7
count: 1
-
name: "intensity"
offset: 16
datatype: 7
count: 1
-
name: "ring"
offset: 20
datatype: 4
count: 1
Thank you for the answer!
I don't have my setup for now, but I will try soon and keep you posted.
I also was wondering, I don't know if the error can be from that but I am not used to work with Docker, is there something I need to do related to it when I start the calibration?
Or the docker just installed stuffs and now I just need to run: roslaunch cam_lidar_calibration run_optimiser.launch import_samples:=false
?
Docker is a self-contained environment that has all the dependencies required for this package. When you run the docker image it'll automatically build the package for you. Then all you have to do is edit the params.yaml with your specific topics and run roslaunch cam_lidar_calibration run_optimiser.launch
Here is the error message:
process[feature_extraction-1]: started with pid [9911]
process[rviz-2]: started with pid [9912]
process[rqt_reconfigure-3]: started with pid [9913]
[ INFO] [1631289887.310819510]: Input parameters loaded
[ INFO] [1631289887.614885896]: Reconfigure Request: -10.000000 10.000000 -8.000000 8.000000 -5.000000 5.000000
[ INFO] [1631289892.698536899]: Finished init cam_lidar_calibration
Failed to find match for field 'ring'.
and I just verified and I have the same output as you:
fields:
-
name: "x"
offset: 0
datatype: 7
count: 1
-
name: "y"
offset: 4
datatype: 7
count: 1
-
name: "z"
offset: 8
datatype: 7
count: 1
-
name: "intensity"
offset: 12
datatype: 7
count: 1
-
name: "t"
offset: 16
datatype: 6
count: 1
-
name: "ring"
offset: 20
datatype: 6
count: 1
Also, my pointcloud's type is sensor_msgs/PointCloud2
Do you have another idea what could cause this error?
For the Docker, that means that the docker is only used for the installation of the package? After that, you can go directly with the launch file, right?
Thanks a lot!
Could you send over a bag file? I can try to take a look at the data on my end.
You can think of docker as an isolated environment where all the dependencies for the calibration package are installed. You don't need to install anything on your own computer (besides docker of course). Once you enter the container, you can run the launch file the package from within the docker container and it should work automatically.
Thanks for the information about docker, it is clearer for me now!
Here is a link to a bagfile that I did. (It's not the best test, but I am in a deployment right now so I don't have access to my material)
I was able to see my camera image into your rviz, but the point clouds from chessboard and _experimentalregion never appeared..! (I have put my /tf into the bagfile). Maybe it is because of the failed to find 'ring'
error.
https://drive.google.com/file/d/1lhIOTz7QrgWsKO2wNz3332LEnzvhUgme/view?usp=sharing
Thanks and tell me if you need something else!
@ogamache Your Point cloud structure seems to be different from the one used in this repository. It does not have time field. Your error might be because of mismatch in datastructure. I assume you have PointXYZIRT
from velodyne point_types but this repository has ommited the time field and only has PointXYZIR
. Remapping PointXYZIRT
to PointXYZIR
might help.
I had the same issue. The problem was that the datatype of the received msg was a uint8_t instead of a uint16_t as expected. Check the datatype of your msg PointField Message. In your case the ring msg is a uint32_t.
You can resolve that issue by editing the lines 12 and 18 to the datatype in your msg: https://github.com/acfr/cam_lidar_calibration/blob/e01d79fdcaebf31d634fc479f0e7e4775d87d502/include/cam_lidar_calibration/point_xyzir.h#L8-L18
Thanks for your work, I am very excited to try it!
I was trying to start the launch file to do a live calibration, but when I started it, I received an error message related to the lidar. The algorithm was not able to fin the "ring" information from it, even if it is available into the lidar driver (if I open Rviz, I can select the "ring" view)
Do you have an idea why it is not able to fetch the information correctly?
Thank you!