Open Freeskylover opened 4 years ago
Hi @Freeskylover , Here, "relpose" is the transformation from cloud2 frame to cloud1 frame. So, the code is fine. If you have further questions, please open a new issue in hdl_graph_slam repository which is relevant to this topic.
Eigen::Isometry3d relative_pose = keyframe->odom.inverse() * prev_keyframe->odom; Eigen::MatrixXd information = inf_calclator->calc_information_matrix(prev_keyframe->cloud, keyframe->cloud, relative_pose); but here is from cloud1 to cloud2 for the relpose.
Hi @Freeskylover , It seems that code is wrong. It should be:
Eigen::MatrixXd information = inf_calclator->calc_information_matrix(keyframe->cloud, prev_keyframe->cloud, relative_pose);
I'll test and update it later. Thank you for reporting it :)
double InformationMatrixCalculator::calc_fitness_score(const pcl::PointCloud::ConstPtr& cloud1, const pcl::PointCloud::ConstPtr& cloud2, const Eigen::Isometry3d& relpose, double maxrange) {
pcl::search::KdTree::Ptr tree (new pcl::search::KdTree());
tree_->setInputCloud(cloud1);
double fitness_score = 0.0;
// Transform the input dataset using the final transformation pcl::PointCloud input_transformed;
pcl::transformPointCloud (*cloud2, input_transformed, relpose.cast());
I have a question about the relpose. Under my understanding, the relpose is the transformation from clould1 frame to cloud2 frame. so in my thinking, it should exchange cloud1 with cloud2. for example: tree_->setInputCloud(cloud2); pcl::transformPointCloud (*cloud1, input_transformed, relpose.cast());
I am not very sure it , so i am looking for your reply.