Go to the documentation of this file.
42 #include <boost/format.hpp>
53 std::vector<std::string> sensorNames = {
"Sick LMS-1xx",
56 "Kinect / Xtion",
"Sick Tim3xx"};
60 (boost::format(
"SimpleSensorNoiseDataPointsFilter: Error, sensorType id %1% does not exist.") %
sensorType).str());
74 inPlaceFilter(output);
89 noise = computeLaserNoise(0.012, 0.0068, 0.0008, cloud.
features);
94 noise = computeLaserNoise(0.028, 0.0013, 0.0001, cloud.
features);
99 noise = computeLaserNoise(0.018, 0.0006, 0.0015, cloud.
features);
105 const Matrix squaredValues(cloud.
features.topRows(
dim-1).colwise().norm().array().square());
106 noise = squaredValues*(0.5*0.00285);
111 noise = computeLaserNoise(0.004, 0.0053, -0.0092, cloud.
features);
116 (boost::format(
"SimpleSensorNoiseDataPointsFilter: Error, cannot compute noise for sensorType id %1% .") % sensorType).str());
124 const T minRadius,
const T beamAngle,
const T beamConst,
const Matrix& features)
126 typedef typename Eigen::Array<T, 2, Eigen::Dynamic> Array2rows;
128 const int nbPoints = features.cols();
129 const int dim = features.rows();
131 Array2rows evalNoise = Array2rows::Constant(2, nbPoints, minRadius);
132 evalNoise.row(0) = beamAngle * features.topRows(
dim-1).colwise().norm();
133 evalNoise.row(0) += beamConst;
135 return evalNoise.colwise().maxCoeff();
Sick LMS-xxx noise model.
PM::DataPointsFilter DataPointsFilter
SimpleSensorNoiseDataPointsFilter(const Parameters ¶ms=Parameters())
Constructor, uses parameter interface.
#define LOG_INFO_STREAM(args)
void allocateDescriptor(const std::string &name, const unsigned dim)
Makes sure a descriptor of a given name exists, if present, check its dimensions.
Functions and classes that are dependant on scalar type are defined in this templatized class.
PointMatcher< T >::Matrix Matrix
virtual void inPlaceFilter(DataPoints &cloud)
Apply these filters to a point cloud without copying.
Parametrizable::Parameters Parameters
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Parametrizable::InvalidParameter InvalidParameter
Matrix features
features of points in the cloud
The superclass of classes that are constructed using generic parameters. This class provides the para...
const M::mapped_type & get(const M &m, const typename M::key_type &k)
const unsigned sensorType
Parametrizable::InvalidParameter InvalidParameter
virtual DataPoints filter(const DataPoints &input)
Apply filters to input point cloud. This is the non-destructive version and returns a copy.
ConstView getDescriptorViewByName(const std::string &name) const
Get a const view on a descriptor by name, throw an exception if it does not exist.
Matrix computeLaserNoise(const T minRadius, const T beamAngle, const T beamConst, const Matrix &features)