#include <dynamic_reconfigure/server.h>
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/exact_time.h>
#include <pcl/common/transforms.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/sample_consensus/sac_model_plane.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl_msgs/ModelCoefficients.h>
#include <pcl_msgs/PointIndices.h>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <std_msgs/Empty.h>
#include <velo2cam_calibration/StereoConfig.h>
#include <velo2cam_calibration/ClusterCentroids.h>
#include <velo2cam_utils.h>
Go to the source code of this file.
|
void | callback (const PointCloud2::ConstPtr &camera_cloud, const pcl_msgs::ModelCoefficients::ConstPtr &cam_plane_coeffs) |
|
int | main (int argc, char **argv) |
|
void | param_callback (velo2cam_calibration::StereoConfig &config, uint32_t level) |
|
void | warmup_callback (const std_msgs::Empty::ConstPtr &msg) |
|
#define TARGET_NUM_CIRCLES 4 |
void callback |
( |
const PointCloud2::ConstPtr & |
camera_cloud, |
|
|
const pcl_msgs::ModelCoefficients::ConstPtr & |
cam_plane_coeffs |
|
) |
| |
- 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 73 of file stereo_pattern.cpp.
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
void param_callback |
( |
velo2cam_calibration::StereoConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
void warmup_callback |
( |
const std_msgs::Empty::ConstPtr & |
msg | ) |
|
double cluster_tolerance_ |
double delta_height_circles_ |
double delta_width_circles_ |
double min_cluster_factor_ |
double plane_distance_inliers_ |
double target_radius_tolerance_ |