#include <dynamic_reconfigure/server.h>
#include <pcl/common/eigen.h>
#include <pcl/common/transforms.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/filters/passthrough.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl_conversions/pcl_conversions.h>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <std_msgs/Empty.h>
#include <velo2cam_calibration/ClusterCentroids.h>
#include <velo2cam_calibration/LidarConfig.h>
#include <velo2cam_utils.h>
Go to the source code of this file.
|  | 
| void | callback (const PointCloud2::ConstPtr &laser_cloud) | 
|  | 
| int | main (int argc, char **argv) | 
|  | 
| void | param_callback (velo2cam_calibration::LidarConfig &config, uint32_t level) | 
|  | 
| void | warmup_callback (const std_msgs::Empty::ConstPtr &msg) | 
|  | 
◆ PCL_NO_PRECOMPILE
      
        
          | #define PCL_NO_PRECOMPILE | 
      
 
 
◆ callback()
      
        
          | void callback | ( | const PointCloud2::ConstPtr & | laser_cloud | ) |  | 
      
 
Geometric consistency check At this point, circles' center candidates have been computed (found_centers). Now we need to select the set of 4 candidates that best fit the calibration target geometry. To that end, the following steps are followed: 1) Create a cloud with 4 points representing the exact geometry of the calibration target 2) For each possible set of 4 points: compute similarity score 3) Rotate back the candidates with the highest score to their original position in the cloud, and add them to cumulative cloud
Definition at line 74 of file lidar_pattern.cpp.
 
 
◆ main()
      
        
          | int main | ( | int | argc, | 
        
          |  |  | char ** | argv | 
        
          |  | ) |  |  | 
      
 
 
◆ param_callback()
      
        
          | void param_callback | ( | velo2cam_calibration::LidarConfig & | config, | 
        
          |  |  | uint32_t | level | 
        
          |  | ) |  |  | 
      
 
 
◆ warmup_callback()
      
        
          | void warmup_callback | ( | const std_msgs::Empty::ConstPtr & | msg | ) |  | 
      
 
 
◆ angle_threshold_
◆ axis_
◆ centers_pub
◆ centroid_distance_max_
      
        
          | double centroid_distance_max_ | 
      
 
 
◆ centroid_distance_min_
      
        
          | double centroid_distance_min_ | 
      
 
 
◆ circle_radius_
◆ circle_threshold_
◆ clouds_proc_
◆ clouds_used_
◆ cluster_tolerance_
      
        
          | double cluster_tolerance_ | 
      
 
 
◆ coeff_pub
◆ cumulative_cloud
◆ cumulative_pub
◆ delta_height_circles_
      
        
          | double delta_height_circles_ | 
      
 
 
◆ delta_width_circles_
      
        
          | double delta_width_circles_ | 
      
 
 
◆ gradient_threshold_
      
        
          | double gradient_threshold_ | 
      
 
 
◆ min_centers_found_
◆ min_cluster_factor_
      
        
          | double min_cluster_factor_ | 
      
 
 
◆ passthrough_radius_max_
      
        
          | double passthrough_radius_max_ | 
      
 
 
◆ passthrough_radius_min_
      
        
          | double passthrough_radius_min_ | 
      
 
 
◆ pattern_pub
◆ plane_distance_inliers_
      
        
          | double plane_distance_inliers_ | 
      
 
 
◆ plane_threshold_
◆ range_pub
◆ rings_count_
◆ rotated_pattern_pub
◆ save_to_file_
◆ savefile
◆ skip_warmup_
◆ target_radius_tolerance_
      
        
          | double target_radius_tolerance_ | 
      
 
 
◆ threshold_
◆ WARMUP_DONE