Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

更改为适用于KITTI数据集的版本 #287

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 12 additions & 4 deletions LeGO-LOAM/include/utility.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,12 +60,20 @@ extern const string fileDirectory = "/tmp/";
extern const bool useCloudRing = true; // if true, ang_res_y and ang_bottom are not used

// VLP-16
extern const int N_SCAN = 16;
//extern const int N_SCAN = 16;
//extern const int Horizon_SCAN = 1800;
//extern const float ang_res_x = 0.2;
//extern const float ang_res_y = 2.0;
//extern const float ang_bottom = 15.0+0.1;
//extern const int groundScanInd = 7;

//Vel 64
extern const int N_SCAN = 64;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 0.2;
extern const float ang_res_y = 2.0;
extern const float ang_bottom = 15.0+0.1;
extern const int groundScanInd = 7;
extern const float ang_res_y = 0.427;
extern const float ang_bottom = 24.9;
extern const int groundScanInd = 50;

// HDL-32E
// extern const int N_SCAN = 32;
Expand Down
26 changes: 26 additions & 0 deletions LeGO-LOAM/src/mapOptmization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -727,6 +727,32 @@ class mapOptimization{
rate.sleep();
publishGlobalMap();
}

std::cout << "start save final point cloud" << std::endl;
std::cout << "======================================================" << std::endl;

ofstream f;
f.open("/home/roxaneqian/kitti_lego_loam/src/kitti-lego-loam-master/LeGO-LOAM/LeGO-LOAM/getfromcode/traj/myRes.txt");
f << fixed;
//std::cout << "traj roll" << cloudKeyPoses6D->points[0].roll << std::endl;
for(size_t i = 0;i < cloudKeyPoses3D->size();i++)
{
float cy = cos((cloudKeyPoses6D->points[i].yaw)*0.5);
float sy = sin((cloudKeyPoses6D->points[i].yaw)*0.5);
float cr = cos((cloudKeyPoses6D->points[i].roll)*0.5);
float sr = sin((cloudKeyPoses6D->points[i].roll)*0.5);
float cp = cos((cloudKeyPoses6D->points[i].pitch)*0.5);
float sp = sin((cloudKeyPoses6D->points[i].pitch)*0.5);

float w = cy * cp * cr + sy * sp * sr;
float x = cy * cp * sr - sy * sp * cr;
float y = sy * cp * sr + cy * sp * cr;
float z = sy * cp * cr - cy * sp * sr;
//save the traj
f << setprecision(6) << cloudKeyPoses6D->points[i].time << " " << setprecision(9) << cloudKeyPoses6D->points[i].x << " " << cloudKeyPoses6D->points[i].y << " " << cloudKeyPoses6D->points[i].z << " " << x << " " << y << " " << z << " " << w << endl;
}

f.close();
// save final point cloud
pcl::io::savePCDFileASCII(fileDirectory+"finalCloud.pcd", *globalMapKeyFramesDS);

Expand Down