diff --git a/src/main.cpp b/src/main.cpp index a193f3d..0a33493 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -159,6 +159,7 @@ void vidCb(const sensor_msgs::ImageConstPtr img) MinimalImageB minImg((int)cv_ptr->image.cols, (int)cv_ptr->image.rows,(unsigned char*)cv_ptr->image.data); ImageAndExposure* undistImg = undistorter->undistort(&minImg, 1,0, 1.0f); + undistImg->timestamp=cv_ptr->header.stamp.toSec(); fullSystem->addActiveFrame(undistImg, frameID); frameID++; delete undistImg; @@ -173,8 +174,6 @@ int main( int argc, char** argv ) { ros::init(argc, argv, "dso_live"); - - for(int i=1; iprintResult("result1.txt"); for(IOWrap::Output3DWrapper* ow : fullSystem->outputWrapper) { ow->join(); delete ow; } - delete undistorter; delete fullSystem;