You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
thank you very much for your valuable work. I’m not quite sure which parameters to adapt for the different board size. But step by step. I’m trying to calibrate a ZED2i camera (used as mono camera only) together with a velodyne VLP16. You can see the general setup in the picture:
The board in use has half the dimensions when compared to the drawing provided in your repo (1200 mm wide, 500 mm high, circle radius of 60 mm, distances between circles 200 mm and 250 mm in vertical and horizontal direction). The marker size is 9.9 cm. I therefore adapted
the angle threshold to gen.add("angle_threshold", double_t, 0, "Angle threshold for plane segmentation", 0.275, 0, pi/2)
the circle radius to 6 cm gen.add("circle_radius", double_t, 0, "Radius of pattern's circles", 0.06, 0, 1)
again the circle radius to #define TARGET_RADIUS 0.06
with its tolerance to #define GEOMETRY_TOLERANCE 0.03
the different marker size of 9.9 cm to gen.add("marker_size", double_t, 0, "Size of the marker (m)", 0.099, 0.05, 0.25)
again the marker size <arg name="marker_size" value="0.099"/>
and further parameters which I guess belong to the geometry of the board
here to gen.add("delta_width_qr_center", double_t, 0, "width increment from target center to qr center (m)", 0.275, 0, 1)
here to gen.add("delta_height_qr_center", double_t, 0, "height increment from target center to qr center (m)", 0.175, 0, 1)
in src/lidar_pattern.cpp further geometry related parameters: the horizontal circle distance to nh.param("delta_width_circles", delta_width_circles_, 0.25);
and the vertical circle distance to nh.param("delta_height_circles", delta_height_circles_, 0.2);.
I was also trying to increase some parameters, which I guess are related to geometrical tolerances in src/lidar_pattern.cpp L522 to 0.2, L523 to 0.2, L524 to 0.2, L525 to 0.1, L526 to 0.1, L527 to 1.5. However, the board is manufactured rather precisely.
The same in src/mono_qr_pattern.cpp: horizontal circle distance to 25 cm nh.param("delta_width_circles", delta_width_circles_, 0.25);
the marker size to 9.9 cm nh_.param("marker_size", marker_size_, 0.099);
horizontal marker distance to 27.5 cm nh_.param("delta_width_qr_center_", delta_width_qr_center_, 0.275);
vertical marker distance to 17.5 cm nh_.param("delta_height_qr_center_", delta_height_qr_center_, 0.175);
the cluster tolerance to 0.5 h_.param("cluster_tolerance", cluster_tolerance_, 0.5);
and set the debug mode. A .bag of approx. 2-3 min is recorded. I replay it as a loop in pause mode. Then start the calibration for each of the sensors in different terminals:
I then load my pre-adjusted parameters into the rqt_reconfigure GUI. You can see the output in RVIZ here.
with the lidar_pattern_/zyx_filtered cloud in white and the lidar_pattern_/range_filtered_cloud in red.
I reduced the rpm of my velodyne PUCK to 300.
The circle cloud might be a bit unstable. Also, viewing from above I feel like the points of the circle cloud are too sparsely distributed in the x- direction:
When the .bag file is played I get: [ INFO] [1670833454.885590008]: [LiDAR] Processing cloud... Rot. vector: -0.0199767 -0.9998 -0 / Angle: 1.55148 [ INFO] [1670833454.889990658]: [LiDAR] Searching for points in cloud of size 40 [ INFO] [1670833454.890541047]: [LiDAR] Optimized circle segmentation failed, trying unoptimized version [ INFO] [1670833454.890776645]: [LiDAR] Remaining points in cloud 21 [ INFO] [1670833454.891137017]: [LiDAR] Remaining points in cloud 2 [ WARN] [1670833454.891146797]: [LiDAR] Not enough centers: 2 [ INFO] [1670833455.088561642]: [LiDAR] Processing cloud...
I also tried further adjustments regarding the rpm of the sensor. Is this problem related to the adjustment of the filter in rqt_reconfigure? Did I miss to adapt some of the node parameters for the different board size? Should I try to move the board / sensor closer or in another angle?
I would be very happy about any comment. Thanks!
The text was updated successfully, but these errors were encountered:
Dear authors,
thank you very much for your valuable work. I’m not quite sure which parameters to adapt for the different board size. But step by step. I’m trying to calibrate a ZED2i camera (used as mono camera only) together with a velodyne VLP16. You can see the general setup in the picture:
The board in use has half the dimensions when compared to the drawing provided in your repo (1200 mm wide, 500 mm high, circle radius of 60 mm, distances between circles 200 mm and 250 mm in vertical and horizontal direction). The marker size is 9.9 cm. I therefore adapted
the angle threshold to
gen.add("angle_threshold", double_t, 0, "Angle threshold for plane segmentation", 0.275, 0, pi/2)
the circle radius to 6 cm
gen.add("circle_radius", double_t, 0, "Radius of pattern's circles", 0.06, 0, 1)
again the circle radius to
#define TARGET_RADIUS 0.06
with its tolerance to
#define GEOMETRY_TOLERANCE 0.03
the different marker size of 9.9 cm to
gen.add("marker_size", double_t, 0, "Size of the marker (m)", 0.099, 0.05, 0.25)
again the marker size
<arg name="marker_size" value="0.099"/>
and further parameters which I guess belong to the geometry of the board
here to
gen.add("delta_width_qr_center", double_t, 0, "width increment from target center to qr center (m)", 0.275, 0, 1)
here to
gen.add("delta_height_qr_center", double_t, 0, "height increment from target center to qr center (m)", 0.175, 0, 1)
in src/lidar_pattern.cpp further geometry related parameters: the horizontal circle distance to
nh.param("delta_width_circles", delta_width_circles_, 0.25);
and the vertical circle distance to
nh.param("delta_height_circles", delta_height_circles_, 0.2);
.I was also trying to increase some parameters, which I guess are related to geometrical tolerances in src/lidar_pattern.cpp L522 to 0.2, L523 to 0.2, L524 to 0.2, L525 to 0.1, L526 to 0.1, L527 to 1.5. However, the board is manufactured rather precisely.
nh.param("delta_width_circles", delta_width_circles_, 0.25);
nh.param("delta_height_circles", delta_height_circles_, 0.2);
nh_.param("marker_size", marker_size_, 0.099);
nh_.param("delta_width_qr_center_", delta_width_qr_center_, 0.275);
nh_.param("delta_height_qr_center_", delta_height_qr_center_, 0.175);
h_.param("cluster_tolerance", cluster_tolerance_, 0.5);
and set the debug mode. A .bag of approx. 2-3 min is recorded. I replay it as a loop in pause mode. Then start the calibration for each of the sensors in different terminals:
roslaunch velo2cam_calibration mono_pattern.launch camera_name:=/zed2i/zed_node image_topic:=left_raw/image_raw_color frame_name:=zed2i_left_camera_frame
roslaunch velo2cam_calibration lidar_pattern.launch cloud_topic:=/velodyne_points
roslaunch velo2cam_calibration registration.launch sensor1_type:=mono sensor2_type:=lidar
I then load my pre-adjusted parameters into the rqt_reconfigure GUI. You can see the output in RVIZ here.
with the
lidar_pattern_/zyx_filtered
cloud in white and thelidar_pattern_/range_filtered_cloud
in red.I reduced the rpm of my velodyne PUCK to 300.
The circle cloud might be a bit unstable. Also, viewing from above I feel like the points of the circle cloud are too sparsely distributed in the x- direction:
When the .bag file is played I get:
[ INFO] [1670833454.885590008]: [LiDAR] Processing cloud...
Rot. vector: -0.0199767
-0.9998
-0 / Angle: 1.55148
[ INFO] [1670833454.889990658]: [LiDAR] Searching for points in cloud of size 40
[ INFO] [1670833454.890541047]: [LiDAR] Optimized circle segmentation failed, trying unoptimized version
[ INFO] [1670833454.890776645]: [LiDAR] Remaining points in cloud 21
[ INFO] [1670833454.891137017]: [LiDAR] Remaining points in cloud 2
[ WARN] [1670833454.891146797]: [LiDAR] Not enough centers: 2
[ INFO] [1670833455.088561642]: [LiDAR] Processing cloud...
I also tried further adjustments regarding the rpm of the sensor. Is this problem related to the adjustment of the filter in rqt_reconfigure? Did I miss to adapt some of the node parameters for the different board size? Should I try to move the board / sensor closer or in another angle?
I would be very happy about any comment. Thanks!
The text was updated successfully, but these errors were encountered: