diff options
Diffstat (limited to 'src/main.cpp')
-rw-r--r-- | src/main.cpp | 13 |
1 files changed, 4 insertions, 9 deletions
diff --git a/src/main.cpp b/src/main.cpp index ce99968..f1bcd30 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -463,18 +463,14 @@ main(int argc, char **argv) // Open camera YAML Camera cam(argv[1]); -#ifdef ROS_PUBLISH - // Create ROS publisher - ros::init(argc, argv, "refslam"); - ros::NodeHandle n; - ros::Publisher ekfPose = n.advertise<geometry_msgs::PoseStamped>("ekfPose", 100); -#else /* ----- not ROS_PUBLISH ----- */ // Print unicsv header +#ifdef FEATUREMAP + printf("Name,"); +#endif #if STATESIZE==13 printf("GPS-stamp,UTM-Zone,UTM-Ch,UTM-North,UTM-East,Altitude,Vel-X,Vel-Y,Vel-Z,Quat-X,Quat-Y,Quat-Z,Quat-W,Bias-X,Bias-Y,Bias-Z,Nfeats\n"); #else printf("UTM-Zone,UTM-Ch,UTM-North,UTM-East,Altitude,Vel-X,Vel-Y,Vel-Z,Bias-X,Bias-Y,Bias-Z,Nfeats\n"); -#endif #endif /* ----- not ROS_PUBLISH ----- */ // read params file FILE *pfin; @@ -531,8 +527,7 @@ main(int argc, char **argv) #endif //printf("%f,", msg.stamp.secs+msg.stamp.nsecs*1e-9); if (seenutm && seenpva && seencov) { - printf("%f,", msg.stamp.secs+msg.stamp.nsecs*1e-9); - mu.unicsv(); + mu.unicsv(msg.stamp.secs+msg.stamp.nsecs*1e-9); } break; |