pointCloudToVtk.cpp
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 
00009 #include "pointmatcher_ros/point_cloud.h"
00010 #include "pointmatcher_ros/transform.h"
00011 #include "pointmatcher_ros/get_params_from_server.h"
00012 #include "pointmatcher_ros/aliases.h"
00013 #include "pointmatcher_ros/ros_logger.h"
00014 
00015 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00016 #include "nav_msgs/Odometry.h"
00017 #include "tf/transform_broadcaster.h"
00018 #include "tf_conversions/tf_eigen.h"
00019 #include "tf/transform_listener.h"
00020 
00021 using namespace std;
00022 using namespace PointMatcherSupport;
00023 
00024 class ExportVtk
00025 {
00026         ros::NodeHandle& n;
00027         
00028         ros::Subscriber cloudSub;
00029         string cloudTopic;
00030         string mapFrame;
00031 
00032         tf::TransformListener tf_listener;
00033         std::shared_ptr<PM::Transformation> transformation;
00034 
00035 public:
00036         ExportVtk(ros::NodeHandle& n);
00037         void gotCloud(const sensor_msgs::PointCloud2& cloudMsg);
00038 };
00039 
00040 ExportVtk::ExportVtk(ros::NodeHandle& n):
00041         n(n),
00042         transformation(PM::get().TransformationRegistrar.create("RigidTransformation"))
00043 {
00044         // ROS initialization
00045         cloudTopic = getParam<string>("cloudTopic", "/static_point_cloud");
00046         cloudSub = n.subscribe(cloudTopic, 100, &ExportVtk::gotCloud, this);
00047         
00048         // Parameters for 3D map
00049         mapFrame= getParam<string>("mapFrameId", "/map");
00050 }
00051 
00052 
00053 void ExportVtk::gotCloud(const sensor_msgs::PointCloud2& cloudMsgIn)
00054 {
00055         const DP inCloud(PointMatcher_ros::rosMsgToPointMatcherCloud<float>(cloudMsgIn));
00056         
00057         const PM::TransformationParameters tr(PointMatcher_ros::transformListenerToEigenMatrix<float>(tf_listener, cloudMsgIn.header.frame_id, mapFrame, cloudMsgIn.header.stamp));
00058         
00059         const DP outCloud(transformation->compute(inCloud, tr));
00060         
00061         if (outCloud.features.cols() == 0)
00062         {
00063                 ROS_ERROR("I found no good points in the cloud");
00064                 return;
00065         }
00066         else
00067         {
00068                 ROS_INFO("Saving cloud");
00069         }
00070         
00071         stringstream nameStream;
00072         nameStream << "." << cloudTopic << "_" << cloudMsgIn.header.seq << ".vtk";
00073         outCloud.save(nameStream.str());
00074 }
00075 
00076 // Main function supporting the ExportVtk class
00077 int main(int argc, char **argv)
00078 {
00079         ros::init(argc, argv, "pointCloudToVtk_node");
00080         ros::NodeHandle n;
00081         ExportVtk exporter(n);
00082         ros::spin();
00083         
00084         return 0;
00085 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


point_cloud_vtk_tools
Author(s): François Pomerleau and Stéphane Magnenat
autogenerated on Tue Dec 18 2012 01:33:19