MRPT  2.0.4
T3DPointsTo2DScanParams.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <string>
12 
13 namespace mrpt::obs
14 {
15 /** Used in CObservation3DRangeScan::convertTo2DScan()
16  * \ingroup mrpt_obs_grp
17  */
19 {
20  /** The sensor label that will have the newly created observation. */
21  std::string sensorLabel;
22  /** (Default=5 degrees) [Only if use_origin_sensor_pose=false] The upper &
23  * lower half-FOV angle (in radians). */
25  /** (Default:-inf, +inf) [Only if use_origin_sensor_pose=true] Only obstacle
26  * points with Z coordinates within the range [z_min,z_max] will be taken
27  * into account. */
28  double z_min, z_max;
29  /** (Default=1.2=120%) How many more laser scans rays to create (read docs
30  * for CObservation3DRangeScan::convertTo2DScan()). */
31  double oversampling_ratio{1.2};
32 
33  /** (Default:false) If `false`, the conversion will be such that the 2D
34  * observation pose on the robot coincides with that in the original 3D
35  * range scan.
36  * If `true`, the sensed points will be "reprojected" as seen from a sensor
37  * pose at the robot/vehicle frame origin (and angle_sup, angle_inf will be
38  * ignored) */
40 
42 };
43 } // namespace mrpt::obs
std::string sensorLabel
The sensor label that will have the newly created observation.
double oversampling_ratio
(Default=1.2=120%) How many more laser scans rays to create (read docs for CObservation3DRangeScan::c...
double angle_sup
(Default=5 degrees) [Only if use_origin_sensor_pose=false] The upper & lower half-FOV angle (in radia...
double z_min
(Default:-inf, +inf) [Only if use_origin_sensor_pose=true] Only obstacle points with Z coordinates wi...
Used in CObservation3DRangeScan::convertTo2DScan()
This namespace contains representation of robot actions and observations.
bool use_origin_sensor_pose
(Default:false) If false, the conversion will be such that the 2D observation pose on the robot coinc...



Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020