matcher_service.cpp
Go to the documentation of this file.
00001 #include <fstream>
00002 
00003 #include "ros/ros.h"
00004 
00005 #include "pointmatcher/PointMatcher.h"
00006 
00007 #include "pointmatcher_ros/point_cloud.h"
00008 #include "pointmatcher_ros/transform.h"
00009 #include "pointmatcher_ros/get_params_from_server.h"
00010 #include "pointmatcher_ros/aliases.h"
00011 #include "pointmatcher_ros/ros_logger.h"
00012 
00013 #include "modular_cloud_matcher/MatchClouds.h"
00014 
00015 #include "tf/tf.h"
00016 
00017 using namespace std;
00018 
00019 class CloudMatcher
00020 {
00021         ros::NodeHandle& n;
00022         
00023         PM::ICP icp;
00024         
00025         ros::ServiceServer service;
00026         
00027 public:
00028         CloudMatcher(ros::NodeHandle& n);
00029         bool match(modular_cloud_matcher::MatchClouds::Request& req, modular_cloud_matcher::MatchClouds::Response& res);
00030 };
00031 
00032 CloudMatcher::CloudMatcher(ros::NodeHandle& n):
00033         n(n),
00034         service(n.advertiseService("match_clouds", &CloudMatcher::match, this))
00035 {
00036         // load config
00037         string configFileName;
00038         if (ros::param::get("~config", configFileName))
00039         {
00040                 ifstream ifs(configFileName.c_str());
00041                 if (ifs.good())
00042                 {
00043                         icp.loadFromYaml(ifs);
00044                 }
00045                 else
00046                 {
00047                         ROS_ERROR_STREAM("Cannot load config from YAML file " << configFileName);
00048                         icp.setDefault();
00049                 }
00050         }
00051         else
00052         {
00053                 ROS_WARN_STREAM("No config file specified, using default ICP chain.");
00054                 icp.setDefault();
00055         }
00056         
00057         // replace logger
00058         if (getParam<bool>("useROSLogger", false))
00059                 PointMatcherSupport::setLogger(new PointMatcherSupport::ROSLogger);
00060 }
00061 
00062 bool CloudMatcher::match(modular_cloud_matcher::MatchClouds::Request& req, modular_cloud_matcher::MatchClouds::Response& res)
00063 {
00064         // get and check reference
00065         const DP referenceCloud(PointMatcher_ros::rosMsgToPointMatcherCloud<float>(req.reference));
00066         const unsigned referenceGoodCount(referenceCloud.features.cols());
00067         const unsigned referencePointCount(req.reference.width * req.reference.height);
00068         const double referenceGoodRatio(double(referenceGoodCount) / double(referencePointCount));
00069         
00070         if (referenceGoodCount == 0)
00071         {
00072                 ROS_ERROR("I found no good points in the reference cloud");
00073                 return false;
00074         }
00075         if (referenceGoodRatio < 0.5)
00076         {
00077                 ROS_WARN_STREAM("Partial reference cloud! Missing " << 100 - referenceGoodRatio*100.0 << "% of the cloud (received " << referenceGoodCount << ")");
00078         }
00079         
00080         // get and check reading
00081         const DP readingCloud(PointMatcher_ros::rosMsgToPointMatcherCloud<float>(req.readings));
00082         const unsigned readingGoodCount(referenceCloud.features.cols());
00083         const unsigned readingPointCount(req.readings.width * req.readings.height);
00084         const double readingGoodRatio(double(readingGoodCount) / double(readingPointCount));
00085         
00086         if (readingGoodCount == 0)
00087         {
00088                 ROS_ERROR("I found no good points in the reading cloud");
00089                 return false;
00090         }
00091         if (readingGoodRatio < 0.5)
00092         {
00093                 ROS_WARN_STREAM("Partial reference cloud! Missing " << 100 - readingGoodRatio*100.0 << "% of the cloud (received " << readingGoodCount << ")");
00094         }
00095         
00096         // check dimensions
00097         if (referenceCloud.features.rows() != readingCloud.features.rows())
00098         {
00099                 ROS_ERROR_STREAM("Dimensionality missmatch: reference cloud is " << referenceCloud.features.rows()-1 << " while reading cloud is " << readingCloud.features.rows()-1);
00100                 return false;
00101         }
00102         
00103         // call ICP
00104         try 
00105         {
00106                 const PM::TransformationParameters transform(icp(readingCloud, referenceCloud));
00107                 tf::transformTFToMsg(PointMatcher_ros::eigenMatrixToTransform<Scalar>(transform), res.transform);
00108                 ROS_INFO_STREAM("match ratio: " << icp.errorMinimizer->getWeightedPointUsedRatio() << endl);
00109         }
00110         catch (PM::ConvergenceError error)
00111         {
00112                 ROS_ERROR_STREAM("ICP failed to converge: " << error.what());
00113                 return false;
00114         }
00115         
00116         return true;
00117 }
00118 
00119 
00120 int main(int argc, char **argv)
00121 {
00122         ros::init(argc, argv, "cloud_matcher_service");
00123         ros::NodeHandle n;
00124         
00125         CloudMatcher matcher(n);
00126         
00127         ros::spin();
00128         
00129         return 0;
00130 }
00131 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


modular_cloud_matcher
Author(s): François Pomerleau and Stéphane Magnenat
autogenerated on Mon Dec 17 2012 20:43:32