42 #include <boost/format.hpp>
61 inPlaceFilter(output);
70 throw InvalidField(
"RemoveSensorBiasDataPointsFilter: Error, cannot find incidence angles in descriptors.");
73 throw InvalidField(
"RemoveSensorBiasDataPointsFilter: Error, cannot find observationDirections in descriptors.");
78 double aperture, k1, k2;
84 aperture = SensorParameters::LMS_1XX.aperture;
85 k1 = SensorParameters::LMS_1XX.k1;
86 k2 = SensorParameters::LMS_1XX.k2;
91 aperture = SensorParameters::HDL_32E.aperture;
92 k1 = SensorParameters::HDL_32E.k1;
93 k2 = SensorParameters::HDL_32E.k2;
98 (boost::format(
"RemoveSensorBiasDataPointsFilter: Error, cannot remove bias for sensorType id %1% .") % sensorType).str());
102 const std::size_t dim = cloud.
features.rows();
105 assert(dim == 3 or dim == 4);
108 for(std::size_t i = 0; i < nbPts; ++i)
110 const Vector vObs = observationDirections.col(i);
112 const double depth = vObs.norm();
113 const T incidence = incidenceAngles(0, i);
117 if(not std::isnan(incidence) and incidence >= 0. and incidence < angleThreshold)
119 const double correction = k1 * diffDist(depth, incidence, aperture) + k2 * ratioCurvature(depth, incidence, aperture);
122 p.head(dim-1) += correction * vObs.normalized();
134 const double sigma = tau / std::sqrt(2. * M_PI);
135 const double w0 = lambda_light / (M_PI * aperture);
138 const double K1 =
std::pow(std::cos(theta), 3);
139 const double K2 = 3. *
std::pow(std::cos(theta), 2) * std::sin(theta);
140 const double L1 = pulse_intensity *
std::pow(w0 / (aperture * depth * std::cos(theta)), 2) *
141 std::sqrt(M_PI) * std::erf(aperture * std::sqrt(A)) / (2. *
std::pow(A, 3. / 2.));
142 const double L2 = pulse_intensity *
std::pow(w0 / (aperture * depth * std::cos(theta)), 2) * K2 / (2. * A);
144 const double a0 = 2. * A * K1 * L1;
145 const double a1 = -(2. * std::tan(theta) * depth *
146 (L1 * K2 - 2. * L2 * aperture * std::exp(-A *
std::pow(aperture, 2)))) / (
std::pow(sigma, 2) * c);
147 const double a2 = -L1 * 2. * A * K1 * (
std::pow(sigma * c * std::cos(theta), 2) * A + 2. *
std::pow(std::cos(theta) * depth, 2) - 2. *
std::pow(depth, 2)) /
149 const double a3 = L1 * K2 * depth * std::tan(theta) * (
std::pow(sigma * c, 2) * A - 2. *
std::pow(depth * std::tan(theta), 2)) /
152 return {a0, a1, a2, a3};
158 static constexpr
double epsilon = 1e-5;
160 const std::array<double, 4> a = getCoefficients(depth, theta, aperture);
167 Tmax = (-2 * a[2] - std::sqrt(4 *
pow(a[2], 2) - 12 * a[1] * a[3])) / (6 * a[3]);
169 return Tmax * c / 2.;
175 static constexpr
double epsilon = 1e-5;
176 const std::array<double,4> a = getCoefficients(depth, theta, aperture);
177 const std::array<double,4> b = getCoefficients(depth, 0., aperture);
184 Tmax = ( -2 * a[2] - std::sqrt(4 *
std::pow(a[2], 2) - 12 * a[1] * a[3])) / (6 * a[3]);
186 return 1. - 2 * b[2] / (2 * a[2] + 6 * Tmax * a[3]);