一、文件格式
timestamps.txt 如下:
二、程序
int main(int argc, char** argv)
{
ros::init(argc, argv, "vins_estimator");
ros::NodeHandle n("~");
ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info);
if(argc != 3)
{
printf("please intput: rosrun vins camera_IMU_GPS_test [config file] [data folder] \n"
"for example: rosrun vins camera_IMU_GPS_test "
"~/catkin_ws/src/VINS-Fusion/config/test_data/stereo_imu_gps_config.yaml "
"/home/hltt3838/kitti_data/2011_10_03_drive_0027_sync/ \n");
return 1;
}
string config_file = argv[1]; //stereo_imu_gps_config.yaml
printf("config_file: %s\n", argv[1]);
string sequence = argv[2];//---/home/hltt3838/kitti_data/2011_10_03_drive_0027_sync/
printf("read sequence: %s\n", argv[2]);
string dataPath = sequence + "/";
//读取图像时间
FILE* file;
file = std::fopen((dataPath + "image_00/timestamps.txt").c_str() , "r");
if(file == NULL){
printf("cannot find file: %simage_00/timestamps.txt \n", dataPath.c_str());
ROS_BREAK();
return 0;
}
vector<double> imageTimeList;
int year, month, day;
int hour, minute;
double second;//这里时间读取的格式- :和 真实的数据,看一下,学习一下
while (fscanf(file, "%d-%d-%d %d:%d:%lf", &year, &month, &day, &hour, &minute, &second) != EOF)
{
imageTimeList.push_back(hour * 60 * 60 + minute * 60 + second);
}
std::fclose(file);
知识点1:
当我们在端口输入:
//rosrun vins camera_IMU_GPS_test [config file] [data folder]
rosrun vins camera_IMU_GPS_test stereo_imu_gps_config.yaml 2011_10_03_drive_0027_sync
那么
argv[1] = stereo_imu_gps_config.yaml
argv[2] = 2011_10_03_drive_0027_sync
再者命名:
string config_file = argv[1];
string sequence = argv[2];
知识点2:
当然,我们也可以定义如下:
string sequence = "home//hltt3838//kitti_data//2011_10_03_drive_0027_sync//";
主要是下面,我们与原来的数据格式要一致!
//年-月-日 时:分:秒
while (fscanf(file, "%d-%d-%d %d:%d:%lf", &year, &month, &day, &hour, &minute, &second) != EOF)
{
imageTimeList.push_back(hour * 60 * 60 + minute * 60 + second);
}
//注意:相机和GPS数据都是10HZ,如果不是应该怎么写
for (size_t i = 0; i < imageTimeList.size(); i++)
{
//读取GPS信息
FILE* GPSFile;
string GPSFilePath = dataPath + "oxts/data/" + ss.str() + ".txt";
GPSFile = std::fopen(GPSFilePath.c_str() , "r");
if(GPSFile == NULL){
printf("cannot find file: %s\n", GPSFilePath.c_str());
ROS_BREAK();
return 0;
}
double lat, lon, alt, roll, pitch, yaw;
double vn, ve, vf, vl, vu;
double ax, ay, az, af, al, au;
double wx, wy, wz, wf, wl, wu;
double pos_accuracy, vel_accuracy;
double navstat, numsats;
double velmode, orimode;
fscanf(GPSFile, "%lf %lf %lf %lf %lf %lf ", &lat, &lon, &alt, &roll, &pitch, &yaw);
fscanf(GPSFile, "%lf %lf %lf %lf %lf ", &vn, &ve, &vf, &vl, &vu);
fscanf(GPSFile, "%lf %lf %lf %lf %lf %lf ", &ax, &ay, &az, &af, &al, &au);
fscanf(GPSFile, "%lf %lf %lf %lf %lf %lf ", &wx, &wy, &wz, &wf, &wl, &wu);
fscanf(GPSFile, "%lf %lf %lf %lf %lf %lf ", &pos_accuracy, &vel_accuracy, &navstat, &numsats, &velmode, &orimode);
std::fclose(GPSFile);
sensor_msgs::NavSatFix gps_position;
gps_position.header.frame_id = "NED";
gps_position.header.stamp = ros::Time(imgTime);
gps_position.status.status = navstat;
gps_position.status.service = numsats;
gps_position.latitude = lat;
gps_position.longitude = lon;
gps_position.altitude = alt;
gps_position.position_covariance[0] = pos_accuracy;
pubGPS.publish(gps_position);
}