#include <pcl/registration/transformation_estimation_svd.h>#include <pcl_conversions/pcl_conversions.h>#include <pcl_ros/transforms.h>#include <ros/package.h>#include <ros/ros.h>#include <std_msgs/Empty.h>#include <std_msgs/Int32.h>#include <tf/tf.h>#include <tf/transform_broadcaster.h>#include <tf/transform_listener.h>#include <tinyxml.h>#include <velo2cam_calibration/ClusterCentroids.h>#include <velo2cam_utils.h>
Go to the source code of this file.
| Macros | |
| #define | PCL_NO_PRECOMPILE | 
| Typedefs | |
| typedef Eigen::Matrix< double, 12, 12 > | Matrix12d | 
| typedef Eigen::Matrix< double, 12, 1 > | Vector12d | 
| Functions | |
| void | calibrateExtrinsics (int seek_iter=-1) | 
| int | main (int argc, char **argv) | 
| void | sensor1_callback (const velo2cam_calibration::ClusterCentroids::ConstPtr sensor1_centroids) | 
| std::vector< pcl::PointXYZ > | sensor1_vector (4) | 
| void | sensor2_callback (velo2cam_calibration::ClusterCentroids::ConstPtr sensor2_centroids) | 
| std::vector< pcl::PointXYZ > | sensor2_vector (4) | 
| #define PCL_NO_PRECOMPILE | 
Definition at line 26 of file velo2cam_calibration.cpp.
| typedef Eigen::Matrix<double, 12, 12> Matrix12d | 
Definition at line 65 of file velo2cam_calibration.cpp.
| typedef Eigen::Matrix<double, 12, 1> Vector12d | 
Definition at line 66 of file velo2cam_calibration.cpp.
| void calibrateExtrinsics | ( | int | seek_iter = -1 | ) | 
Definition at line 101 of file velo2cam_calibration.cpp.
| int main | ( | int | argc, | 
| char ** | argv | ||
| ) | 
Definition at line 662 of file velo2cam_calibration.cpp.
| void sensor1_callback | ( | const velo2cam_calibration::ClusterCentroids::ConstPtr | sensor1_centroids | ) | 
Definition at line 273 of file velo2cam_calibration.cpp.
| std::vector<pcl::PointXYZ> sensor1_vector | ( | 4 | ) | 
| void sensor2_callback | ( | velo2cam_calibration::ClusterCentroids::ConstPtr | sensor2_centroids | ) | 
Definition at line 461 of file velo2cam_calibration.cpp.
| std::vector<pcl::PointXYZ> sensor2_vector | ( | 4 | ) | 
| bool calibration_ended | 
Definition at line 85 of file velo2cam_calibration.cpp.
| ros::Publisher clusters_sensor1_pub | 
Definition at line 45 of file velo2cam_calibration.cpp.
| ros::Publisher clusters_sensor2_pub | 
Definition at line 45 of file velo2cam_calibration.cpp.
| ros::Publisher colour_sensor1_pub | 
Definition at line 46 of file velo2cam_calibration.cpp.
| ros::Publisher colour_sensor2_pub | 
Definition at line 46 of file velo2cam_calibration.cpp.
| bool is_sensor1_cam | 
Definition at line 58 of file velo2cam_calibration.cpp.
| bool is_sensor2_cam | 
Definition at line 58 of file velo2cam_calibration.cpp.
| pcl::PointCloud<pcl::PointXYZI>::Ptr isensor1_cloud | 
Definition at line 53 of file velo2cam_calibration.cpp.
| pcl::PointCloud<pcl::PointXYZI>::Ptr isensor2_cloud | 
Definition at line 53 of file velo2cam_calibration.cpp.
| ros::Publisher iterations_pub | 
Definition at line 48 of file velo2cam_calibration.cpp.
| int nFrames | 
Definition at line 49 of file velo2cam_calibration.cpp.
| ros::NodeHandle* nh_ | 
Definition at line 97 of file velo2cam_calibration.cpp.
| bool publish_tf_ | 
Definition at line 84 of file velo2cam_calibration.cpp.
| bool results_every_pose | 
Definition at line 86 of file velo2cam_calibration.cpp.
| int S1_WARMUP_COUNT = 0 | 
Definition at line 77 of file velo2cam_calibration.cpp.
| bool S1_WARMUP_DONE = false | 
Definition at line 78 of file velo2cam_calibration.cpp.
| int S2_WARMUP_COUNT = 0 | 
Definition at line 77 of file velo2cam_calibration.cpp.
| bool S2_WARMUP_DONE = false | 
Definition at line 78 of file velo2cam_calibration.cpp.
| bool save_to_file_ | 
Definition at line 83 of file velo2cam_calibration.cpp.
| std::ofstream savefile | 
Definition at line 90 of file velo2cam_calibration.cpp.
| std::vector<std::vector<std::tuple<int, int, pcl::PointCloud<pcl::PointXYZ>, std::vector<pcl::PointXYZ> > > > sensor1_buffer | 
Definition at line 72 of file velo2cam_calibration.cpp.
| pcl::PointCloud<pcl::PointXYZ>::Ptr sensor1_cloud | 
Definition at line 52 of file velo2cam_calibration.cpp.
| long int sensor1_count | 
Definition at line 88 of file velo2cam_calibration.cpp.
| string sensor1_frame_id = "" | 
Definition at line 60 of file velo2cam_calibration.cpp.
| string sensor1_rotated_frame_id = "" | 
Definition at line 61 of file velo2cam_calibration.cpp.
| ros::Subscriber sensor1_sub | 
Definition at line 99 of file velo2cam_calibration.cpp.
| bool sensor1Received | 
Definition at line 50 of file velo2cam_calibration.cpp.
| std::vector<std::vector<std::tuple<int, int, pcl::PointCloud<pcl::PointXYZ>, std::vector<pcl::PointXYZ> > > > sensor2_buffer | 
Definition at line 75 of file velo2cam_calibration.cpp.
| pcl::PointCloud<pcl::PointXYZ>::Ptr sensor2_cloud | 
Definition at line 52 of file velo2cam_calibration.cpp.
| long int sensor2_count | 
Definition at line 88 of file velo2cam_calibration.cpp.
| string sensor2_frame_id = "" | 
Definition at line 62 of file velo2cam_calibration.cpp.
| string sensor2_rotated_frame_id = "" | 
Definition at line 63 of file velo2cam_calibration.cpp.
| ros::Subscriber sensor2_sub | 
Definition at line 99 of file velo2cam_calibration.cpp.
| bool sensor2Received | 
Definition at line 50 of file velo2cam_calibration.cpp.
| ros::Publisher sensor_switch_pub | 
Definition at line 47 of file velo2cam_calibration.cpp.
| bool single_pose_mode | 
Definition at line 59 of file velo2cam_calibration.cpp.
| bool skip_warmup | 
Definition at line 59 of file velo2cam_calibration.cpp.
| bool sync_iterations | 
Definition at line 82 of file velo2cam_calibration.cpp.
| int TARGET_ITERATIONS = 30 | 
Definition at line 80 of file velo2cam_calibration.cpp.
| int TARGET_POSITIONS_COUNT = 0 | 
Definition at line 79 of file velo2cam_calibration.cpp.
| tf::StampedTransform tf_sensor1_sensor2 | 
Definition at line 56 of file velo2cam_calibration.cpp.
| tf::Transform transf | 
Definition at line 68 of file velo2cam_calibration.cpp.