Go to the documentation of this file.00001 #include <fstream>
00002 #include <memory>
00003
00004 #include "ros/ros.h"
00005 #include "ros/console.h"
00006
00007 #include "pointmatcher/PointMatcher.h"
00008 #include "pointmatcher/IO.h"
00009
00010 #include "pointmatcher_ros/point_cloud.h"
00011 #include "pointmatcher_ros/transform.h"
00012 #include "pointmatcher_ros/get_params_from_server.h"
00013 #include "pointmatcher_ros/aliases.h"
00014 #include "pointmatcher_ros/ros_logger.h"
00015
00016
00017 using namespace std;
00018 using namespace PointMatcherSupport;
00019
00020 class PublishVTK
00021 {
00022 typedef PointMatcherIO<float> PMIO;
00023
00024 ros::NodeHandle& n;
00025
00026
00027 const string mapFrame;
00028 const string cloudTopic;
00029 const string csvListFiles;
00030 const string dataDirectory;
00031 const string singleFile;
00032 const double publishRate;
00033
00034 ros::Publisher cloudPub;
00035 PMIO::FileInfoVector list;
00036 unsigned currentId;
00037
00038 public:
00039 PublishVTK(ros::NodeHandle& n);
00040 void publish();
00041 void run();
00042 };
00043
00044 PublishVTK::PublishVTK(ros::NodeHandle& n):
00045 n(n),
00046 mapFrame(getParam<string>("mapFrameId", "/map")),
00047 cloudTopic(getParam<string>("cloudTopic", "/point_cloud")),
00048 csvListFiles(getParam<string>("csvListFiles", "")),
00049 dataDirectory(getParam<string>("dataDirectory", "")),
00050 singleFile(getParam<string>("singleFile", "")),
00051 publishRate(getParam<double>("publishRate", 1.0))
00052 {
00053
00054 cloudPub = n.advertise<sensor_msgs::PointCloud2>(cloudTopic, 1);
00055
00056 if(csvListFiles != "")
00057 {
00058 list = PMIO::FileInfoVector(csvListFiles, dataDirectory);
00059 }
00060 currentId = 0;
00061 }
00062
00063 void PublishVTK::publish()
00064 {
00065 if (cloudPub.getNumSubscribers())
00066 {
00067 DP cloud;
00068 if(singleFile != "")
00069 cloud = DP::load(singleFile);
00070 else
00071 {
00072 if(csvListFiles != "")
00073 {
00074 cout << endl << "Press <ENTER> to continue or <CTRL-c> to exit" << endl;
00075 cin.clear();
00076 cin.ignore(INT_MAX, '\n');
00077 ROS_INFO_STREAM("Publishing file [" << currentId << "/" << list.size() << "]: " << list[currentId].readingFileName);
00078 cloud = DP::load(list[currentId].readingFileName);
00079 currentId++;
00080 if(currentId >= list.size())
00081 {
00082 cout << endl << "Press <ENTER> to restart or <CTRL-c> to exit" << endl;
00083 cin.clear();
00084 cin.ignore(INT_MAX, '\n');
00085 currentId = 0;
00086 }
00087 }
00088 }
00089
00090 if(singleFile != "" || csvListFiles != "")
00091 cloudPub.publish(PointMatcher_ros::pointMatcherCloudToRosMsg<float>(cloud, mapFrame, ros::Time::now()));
00092 }
00093 }
00094
00095 void PublishVTK::run()
00096 {
00097 ros::Rate r(publishRate);
00098 while (ros::ok())
00099 {
00100 publish();
00101 r.sleep();
00102 }
00103 }
00104
00105
00106 int main(int argc, char **argv)
00107 {
00108
00109 ros::init(argc, argv, "VtkToPointCloud_node");
00110 ros::NodeHandle n;
00111 PublishVTK pub(n);
00112 pub.run();
00113
00114 return 0;
00115 }