视觉里程计结果输出
estimator\src\utility\visualization.cpp pubOdometry函数中(第151行)
// write result to file
ofstream foutC(VINS_RESULT_PATH, ios::app);
foutC.setf(ios::fixed, ios::floatfield);
foutC.precision(0);
foutC << header.stamp.toSec() * 1e9 << ",";
foutC.precision(5);
foutC << estimator.Ps[WINDOW_SIZE].x() << ","
<< estimator.Ps[WINDOW_SIZE].y() << ","
<< estimator.Ps[WINDOW_SIZE].z() << ","
<< tmp_Q.w() << ","
<< tmp_Q.x() << ","
<< tmp_Q.y() << ","
<< tmp_Q.z() << ","
<< estimator.Vs[WINDOW_SIZE].x() << ","
<< estimator.Vs[WINDOW_SIZE].y() << ","
<< estimator.Vs[WINDOW_SIZE].z() << "," << endl;
foutC.close();
GNSS结果输出
estimator\src\utility\visualization.cpp pubGnssResult函数中(第237行)
// write GNSS result to file
ofstream gnss_output(GNSS_RESULT_PATH, ios::app);
gnss_output.setf(ios::fixed, ios::floatfield);
gnss_output.precision(0);
gnss_output << header.stamp.toSec() * 1e9 << ',';
gnss_output << gnss_ts * 1e9 << ',';
gnss_output.precision(5);
gnss_output << estimator.ecef_pos(0) << ','
<< estimator.ecef_pos(1) << ','
<< estimator.ecef_pos(2) << ','
<< estimator.yaw_enu_local << ','
<< estimator.para_rcv_dt[(WINDOW_SIZE)*4+0] << ','
<< estimator.para_rcv_dt[(WINDOW_SIZE)*4+1] << ','
<< estimator.para_rcv_dt[(WINDOW_SIZE)*4+2] << ','
<< estimator.para_rcv_dt[(WINDOW_SIZE)*4+3] << ','
<< estimator.para_rcv_ddt[WINDOW_SIZE] << ','
<< estimator.anc_ecef(0) << ','
<< estimator.anc_ecef(1) << ','
<< estimator.anc_ecef(2) << '\n';
gnss_output.close();
文件保存位置
home下output文件