19 #include <Eigen/Dense> 33 float threshold,
size_t N,
float noiseStd,
unsigned int decimation,
34 float angleNoiseStd)
const 44 CPose2D sensorPose(sensorPose3D);
49 double A = sensorPose.
phi() +
54 const float free_thres = 1.0f - threshold;
56 for (
size_t i = 0; i < N; i += decimation,
A += AA * decimation)
61 sensorPose.
x(), sensorPose.
y(),
A, out_range, valid,
62 inout_Scan.
maxRange, free_thres, noiseStd, angleNoiseStd);
72 float threshold,
float rangeNoiseStd,
float angleNoiseStd)
const 74 const float free_thres = 1.0f - threshold;
76 for (
auto itR = inout_observation.
begin(); itR != inout_observation.
end();
79 const CPose2D sensorAbsolutePose =
88 double direction = sensorAbsolutePose.
phi() -
92 float min_detected_obs = 0;
93 for (
size_t i = 0; i < nRays; i++, direction += Adir)
98 sensorAbsolutePose.
x(), sensorAbsolutePose.
y(), direction,
100 free_thres, rangeNoiseStd, angleNoiseStd);
102 if (valid && (sim_rang < min_detected_obs || !i))
103 min_detected_obs = sim_rang;
106 itR->sensedDistance = min_detected_obs;
111 const double start_x,
const double start_y,
const double angle_direction,
112 float& out_range,
bool& out_valid,
const double max_range_meters,
113 const float threshold_free,
const double noiseStd,
114 const double angleNoiseStd)
const 125 ::sincos(A_, &Ary, &Arx);
127 const double Arx = cos(A_);
128 const double Ary = sin(A_);
132 const unsigned int max_ray_len =
mrpt::round(max_range_meters / resolution);
133 unsigned int ray_len = 0;
136 #define INTPRECNUMBIT 10 137 #define int_x2idx(_X) (_X >> INTPRECNUMBIT) 138 #define int_y2idx(_Y) (_Y >> INTPRECNUMBIT) 140 auto rxi =
static_cast<int64_t>(
142 auto ryi =
static_cast<int64_t>(
145 const auto Arxi =
static_cast<int64_t>(
146 RAYTRACE_STEP_SIZE_IN_CELL_UNITS * Arx * (1L <<
INTPRECNUMBIT));
147 const auto Aryi =
static_cast<int64_t>(
148 RAYTRACE_STEP_SIZE_IN_CELL_UNITS * Ary * (1L <<
INTPRECNUMBIT));
151 const cellType threshold_free_int = p2l(threshold_free);
155 x < static_cast<int>(size_x) &&
y < static_cast<int>(size_y) &&
156 (hitCellOcc_int = map[
x +
y * size_x]) > threshold_free_int &&
157 ray_len < max_ray_len)
167 if (abs(hitCellOcc_int) <= 1 || static_cast<unsigned>(
x) >= size_x ||
168 static_cast<unsigned>(
y) >= size_y)
171 out_range = max_range_meters;
175 out_range = RAYTRACE_STEP_SIZE_IN_CELL_UNITS * ray_len * resolution;
176 out_valid = (ray_len < max_ray_len);
178 if (noiseStd > 0 && out_valid)
211 CPose3D(x_pose[0], x_pose[1], .0, x_pose[2], .0, .0) +
214 const CPose2D sensorPose(sensorPose3D);
234 sensorPose.
x(), sensorPose.
y(),
A,
range, valid,
249 simulData.
grid =
this;
250 simulData.
params = &in_params;
282 throw std::runtime_error(
283 "[laserScanSimulatorWithUncertainty] Unknown `method` value");
294 for (
unsigned i = 0; i < in_params.
nRays; i++)
303 0.5 * resolution * resolution;
const COccupancyGridMap2D::TLaserSimulUncertaintyParams * params
mrpt::poses::CPosePDFGaussian robotPose
The robot pose Gaussian, in map coordinates.
A namespace of pseudo-random numbers generators of diferent distributions.
void laserScanSimulator(mrpt::obs::CObservation2DRangeScan &inout_Scan, const mrpt::poses::CPose2D &robotPose, float threshold=0.6f, size_t N=361, float noiseStd=0, unsigned int decimation=1, float angleNoiseStd=mrpt::DEG2RAD(.0)) const
Simulates a laser range scan into the current grid map.
A compile-time fixed-size numeric matrix container.
static void func_laserSimul_callback(const mrpt::math::CVectorFixedDouble< 3 > &x_pose, const TFunctorLaserSimulData &fixed_param, mrpt::math::CVectorDouble &y_scanRanges)
Declares a class derived from "CObservation" that encapsules a single range measurement, and associated parameters.
CPose2D mean
The mean value.
float threshold
(Default: 0.6f) The minimum occupancy threshold to consider a cell to be occupied ...
float sensorConeApperture
Cone aperture of each ultrasonic beam, in radians.
mrpt::obs::CObservation2DRangeScanWithUncertainty scanWithUncert
The scan + its uncertainty.
mrpt::poses::CPose3D sensorPose
(Default: at origin) The 6D pose of the sensor on the robot at the moment of starting the scan...
void setScanRange(const size_t i, const float val)
double DEG2RAD(const double x)
Degrees to radians.
Output params for laserScanSimulatorWithUncertainty()
CObservation2DRangeScan rangeScan
The observation with the mean ranges in the scan field.
bool rightToLeft
(Default: true) The scanning direction: true=counterclockwise; false=clockwise
const COccupancyGridMap2D * grid
mrpt::math::CMatrixDouble33 cov
The 3x3 covariance matrix.
float maxRange
The maximum range allowed by the device, in meters (e.g.
#define ASSERT_(f)
Defines an assertion mechanism.
mrpt::math::CVectorDouble rangesMean
The same ranges than in rangeScan.scan[], for convenience as a math vector container, and with double precision.
TLaserSimulUncertaintyParams()
size_t MC_samples
[sumMonteCarlo] MonteCarlo parameter: number of samples (Default: 10)
float aperture
(Default: M_PI) The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180...
This namespace contains representation of robot actions and observations.
double x() const
Common members of all points & poses classes.
unsigned int decimation
(Default: 1) The rays that will be simulated are at indexes: 0, D, 2D, 3D,...
void sonarSimulator(mrpt::obs::CObservationRange &inout_observation, const mrpt::poses::CPose2D &robotPose, float threshold=0.5f, float rangeNoiseStd=0.f, float angleNoiseStd=mrpt::DEG2RAD(0.f)) const
Simulates the observations of a sonar rig into the current grid map.
double UT_alpha
[sumUnscented] UT parameters.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void laserScanSimulatorWithUncertainty(const TLaserSimulUncertaintyParams &in_params, TLaserSimulUncertaintyResult &out_results) const
Like laserScanSimulatorWithUncertainty() (see it for a discussion of most parameters) but taking into...
TLaserSimulUncertaintyResult()
A class for storing an occupancy grid map.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Input params for laserScanSimulatorWithUncertainty()
void simulateScanRay(const double x, const double y, const double angle_direction, float &out_range, bool &out_valid, const double max_range_meters, const float threshold_free=0.4f, const double noiseStd=.0, const double angleNoiseStd=.0) const
Simulate just one "ray" in the grid map.
void resizeScan(const size_t len)
Resizes all data vectors to allocate a given number of scan rays.
const double & phi() const
Get the phi angle of the 2D pose (in radians)
mrpt::math::CMatrixDouble rangesCovar
The covariance matrix for all the ranges in rangeScan.scan[].
TLaserSimulUncertaintyMethod method
(Default: sumMonteCarlo) Select the method to do the uncertainty propagation
float aperture
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees)...
OccGridCellTraits::cellType cellType
The type of the map cells:
static double RAYTRACE_STEP_SIZE_IN_CELL_UNITS
(Default:1.0) Can be set to <1 if a more fine raytracing is needed in sonarSimulator() and laserScanS...
float maxRange
(Default: 80) The maximum range allowed by the device, in meters (e.g.
void resize(std::size_t N, bool zeroNewElements=false)
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
vector_t asVectorVal() const
Return the pose or point as a 1xN vector with all the components (see derived classes for each implem...
bool rightToLeft
The scanning direction: true=counterclockwise; false=clockwise.
double drawGaussian1D_normalized()
Generate a normalized (mean=0, std=1) normally distributed sample.
void setScanRangeValidity(const size_t i, const bool val)
int round(const T value)
Returns the closer integer (int) to x.