Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "SimpleSensorNoise.h"
00036
00037 #include "PointMatcherPrivate.h"
00038
00039 #include <string>
00040 #include <vector>
00041
00042 #include <boost/format.hpp>
00043
00044
00045
00046 template<typename T>
00047 SimpleSensorNoiseDataPointsFilter<T>::SimpleSensorNoiseDataPointsFilter(const Parameters& params):
00048 PointMatcher<T>::DataPointsFilter("SimpleSensorNoiseDataPointsFilter",
00049 SimpleSensorNoiseDataPointsFilter::availableParameters(), params),
00050 sensorType(Parametrizable::get<unsigned>("sensorType")),
00051 gain(Parametrizable::get<T>("gain"))
00052 {
00053 std::vector<std::string> sensorNames = {"Sick LMS-1xx",
00054 "Hokuyo URG-04LX",
00055 "Hokuyo UTM-30LX",
00056 "Kinect / Xtion","Sick Tim3xx"};
00057 if (sensorType >= sensorNames.size())
00058 {
00059 throw InvalidParameter(
00060 (boost::format("SimpleSensorNoiseDataPointsFilter: Error, sensorType id %1% does not exist.") % sensorType).str());
00061 }
00062
00063 LOG_INFO_STREAM("SimpleSensorNoiseDataPointsFilter - using sensor noise model: " << sensorNames[sensorType]);
00064 }
00065
00066
00067
00068
00069 template<typename T>
00070 typename PointMatcher<T>::DataPoints
00071 SimpleSensorNoiseDataPointsFilter<T>::filter(const DataPoints& input)
00072 {
00073 DataPoints output(input);
00074 inPlaceFilter(output);
00075 return output;
00076 }
00077
00078
00079 template<typename T>
00080 void SimpleSensorNoiseDataPointsFilter<T>::inPlaceFilter(DataPoints& cloud)
00081 {
00082 cloud.allocateDescriptor("simpleSensorNoise", 1);
00083 BOOST_AUTO(noise, cloud.getDescriptorViewByName("simpleSensorNoise"));
00084
00085 switch(sensorType)
00086 {
00087 case 0:
00088 {
00089 noise = computeLaserNoise(0.012, 0.0068, 0.0008, cloud.features);
00090 break;
00091 }
00092 case 1:
00093 {
00094 noise = computeLaserNoise(0.028, 0.0013, 0.0001, cloud.features);
00095 break;
00096 }
00097 case 2:
00098 {
00099 noise = computeLaserNoise(0.018, 0.0006, 0.0015, cloud.features);
00100 break;
00101 }
00102 case 3:
00103 {
00104 const int dim = cloud.features.rows();
00105 const Matrix squaredValues(cloud.features.topRows(dim-1).colwise().norm().array().square());
00106 noise = squaredValues*(0.5*0.00285);
00107 break;
00108 }
00109 case 4:
00110 {
00111 noise = computeLaserNoise(0.004, 0.0053, -0.0092, cloud.features);
00112 break;
00113 }
00114 default:
00115 throw InvalidParameter(
00116 (boost::format("SimpleSensorNoiseDataPointsFilter: Error, cannot compute noise for sensorType id %1% .") % sensorType).str());
00117 }
00118
00119 }
00120
00121 template<typename T>
00122 typename PointMatcher<T>::Matrix
00123 SimpleSensorNoiseDataPointsFilter<T>::computeLaserNoise(
00124 const T minRadius, const T beamAngle, const T beamConst, const Matrix& features)
00125 {
00126 typedef typename Eigen::Array<T, 2, Eigen::Dynamic> Array2rows;
00127
00128 const int nbPoints = features.cols();
00129 const int dim = features.rows();
00130
00131 Array2rows evalNoise = Array2rows::Constant(2, nbPoints, minRadius);
00132 evalNoise.row(0) = beamAngle * features.topRows(dim-1).colwise().norm();
00133 evalNoise.row(0) += beamConst;
00134
00135 return evalNoise.colwise().maxCoeff();
00136 }
00137
00138
00139 template struct SimpleSensorNoiseDataPointsFilter<float>;
00140 template struct SimpleSensorNoiseDataPointsFilter<double>;
00141
00142