Commit a0457f09 authored by wangdawei's avatar wangdawei

test

parent e3e8f9a4
...@@ -150,6 +150,10 @@ void AdjustPPK::OnReceivedCloud(const PPointCloud &cloud) ...@@ -150,6 +150,10 @@ void AdjustPPK::OnReceivedCloud(const PPointCloud &cloud)
} }
LocateCloud(cloudInfo); LocateCloud(cloudInfo);
PointCloudJ mathedCloud;
pcl::transformPointCloud(*cloudInfo.frame, mathedCloud, mapPose_.cast<float>());
pcl::io::savePCDFileBinary(ieBaseDir_ + "/baseCloud/" + to_string(cloudInfo.timestamp) + "_matched.pcd", mathedCloud);
} }
void AdjustPPK::LoadPPK() void AdjustPPK::LoadPPK()
...@@ -402,9 +406,6 @@ bool AdjustPPK::LocateCloud(const CloudInfoForMatch &cloudInfo) ...@@ -402,9 +406,6 @@ bool AdjustPPK::LocateCloud(const CloudInfoForMatch &cloudInfo)
guessPose.precision_type = MATCH_PRECISION_HIGH; guessPose.precision_type = MATCH_PRECISION_HIGH;
currMatcher_->MatchPointCloud(cloudInfo.frame, guessPose, finalGnssPose, finalPose); currMatcher_->MatchPointCloud(cloudInfo.frame, guessPose, finalGnssPose, finalPose);
mapPose_ = finalPose.cast<double>(); mapPose_ = finalPose.cast<double>();
PointCloudJ mathedCloud;
pcl::transformPointCloud(*cloudInfo.frame, mathedCloud, finalPose);
pcl::io::savePCDFileBinary(ieBaseDir_ + "/baseCloud/" + to_string(cloudInfo.timestamp) + "_mathed.pcd", mathedCloud);
return true; return true;
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment