9 #ifndef CObservation3DRangeScan_H
10 #define CObservation3DRangeScan_H
32 template <
class POINTMAP>
104 bool m_points3D_external_stored;
105 std::
string m_points3D_external_file;
107 bool m_rangeImage_external_stored;
108 std::
string m_rangeImage_external_file;
112 virtual ~CObservation3DRangeScan( );
121 virtual
void load() const;
125 virtual
void unload();
165 template <class POINTMAP>
167 POINTMAP & dest_pointcloud,
168 const
bool takeIntoAccountSensorPoseOnRobot,
169 const
mrpt::poses::
CPose3D *robotPoseInTheWorld=NULL,
170 const
bool PROJ3D_USE_LUT=true)
172 detail::project3DPointsFromDepthImageInto<POINTMAP>(*
this,dest_pointcloud,takeIntoAccountSensorPoseOnRobot,robotPoseInTheWorld,PROJ3D_USE_LUT);
210 void convertTo2DScan(
212 const std::string & sensorLabel,
213 const double angle_sup =
DEG2RAD(5),
214 const double angle_inf =
DEG2RAD(5),
215 const double oversampling_ratio = 1.2 );
224 void resizePoints3DVectors(
const size_t nPoints);
229 void points3D_getExternalStorageFileAbsolutePath(std::string &out_path)
const;
232 points3D_getExternalStorageFileAbsolutePath(tmp);
235 void points3D_convertToExternalStorage(
const std::string &fileName,
const std::string &use_this_base_dir );
242 void rangeImage_setSize(
const int HEIGHT,
const int WIDTH);
247 void rangeImage_getExternalStorageFileAbsolutePath(std::string &out_path)
const;
250 rangeImage_getExternalStorageFileAbsolutePath(tmp);
253 void rangeImage_convertToExternalStorage(
const std::string &fileName,
const std::string &use_this_base_dir );
285 bool doDepthAndIntensityCamerasCoincide()
const;
307 void getZoneAsObs(
CObservation3DRangeScan &obs,
const unsigned int &r1,
const unsigned int &r2,
const unsigned int &c1,
const unsigned int &c2 );
313 static double recoverCameraCalibrationParameters(
316 const double camera_offset = 0.01 );
363 static const int HAS_RGB = 0;
364 static const int HAS_RGBf = 0;
365 static const int HAS_RGBu8 = 0;
378 template <
typename T>
379 inline void getPointXYZ(
const size_t idx, T &x,T &y, T &z)
const {
385 inline void setPointXYZ(
const size_t idx,
const coords_t x,
const coords_t y,
const coords_t z) {
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
mrpt::utils::CImage confidenceImage
If hasConfidenceImage=true, an image with the "confidence" value [range 0-255] as estimated by the ca...
float maxRange
The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...)
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
std::vector< float > points3D_y
If hasPoints3D=true, the Y coordinates of the 3D point cloud detected by the camera.
TIntensityChannelID intensityImageChannel
The source of the intensityImage; typically the visible channel.
A helper base class for those PointCloudAdapter<> which do not handle RGB data; it declares needed in...
A class for storing images as grayscale or RGB bitmaps.
float coords_t
The type of each point XYZ coordinates.
mrpt::math::CVectorFloat Kzs
void resizePoints3DVectors(const size_t nPoints)
Use this method instead of resizing all three points3D_x, points3D_y & points3D_z to allow the usage ...
void setSensorPose(const CPose3D &newSensorPose)
A general method to change the sensor pose on the robot.
void getSensorPose(CPose3D &out_sensorPose) const
A general method to retrieve the sensor pose on the robot.
#define MRPT_DECLARE_TTYPENAME_PTR(_TYPE)
Only specializations of this class are defined for each enum type of interest.
static TCached3DProjTables m_3dproj_lut
3D point cloud projection look-up-table
This namespace contains algorithms for SLAM, localization, map building, representation of robot's ac...
void project3DPointsFromDepthImageInto(CObservation3DRangeScan &src_obs, POINTMAP &dest_pointcloud, const bool takeIntoAccountSensorPoseOnRobot, const mrpt::poses::CPose3D *robotPoseInTheWorld, const bool PROJ3D_USE_LUT)
bool hasPoints3D
true means the field points3D contains valid data.
std::vector< float > points3D_x
If hasPoints3D=true, the X coordinates of the 3D point cloud detected by the camera.
std::string points3D_getExternalStorageFileAbsolutePath() const
std::string rangeImage_getExternalStorageFile() const
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
std::string points3D_getExternalStorageFile() const
Grayscale or RGB visible channel of the camera sensor.
PointCloudAdapter(const CObservation3DRangeScan &obj)
Constructor (accept a const ref for convenience)
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) ...
Declares a class that represents any robot's observation.
A bidirectional version of std::map, declared as bimap and which actually contains two std...
std::string rangeImage_getExternalStorageFileAbsolutePath() const
void setPointXYZ(const size_t idx, const coords_t x, const coords_t y, const coords_t z)
Set XYZ coordinates of i'th point.
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
mrpt::utils::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
An adapter to different kinds of point cloud object.
void resize(const size_t N)
Set number of points (to uninitialized values)
void rangeImage_forceResetExternalStorage()
Forces marking this observation as non-externally stored - it doesn't anything else apart from reseti...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
void getPointXYZ(const size_t idx, T &x, T &y, T &z) const
Get XYZ coordinates of i'th point.
std::vector< float > points3D_z
If hasPoints3D=true, the Z coordinates of the 3D point cloud detected by the camera.
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
bool hasConfidenceImage
true means the field confidenceImage contains valid data
TIntensityChannelID
Enum type for intensityImageChannel.
bool hasRangeImage
true means the field rangeImage contains valid data
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement (e...
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
slam::CObservation3DRangeScan::TIntensityChannelID enum_t
This class is a "CSerializable" wrapper for "CMatrixFloat".
bool rangeImage_isExternallyStored() const
static void fill(bimap< enum_t, std::string > &m_map)
Look-up-table struct for project3DPointsFromDepthImageInto()
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
mrpt::utils::TCamera cameraParams
Projection parameters of the depth camera.
bool points3D_isExternallyStored() const
CPose3D sensorPose
The 6D pose of the sensor on the robot.
size_t size() const
Get number of points.
CObservation3DRangeScan & m_obj
bool hasIntensityImage
true means the field intensityImage contains valid data
Structure to hold the parameters of a pinhole camera model.
void project3DPointsFromDepthImage(const bool PROJ3D_USE_LUT=true)
This method is equivalent to project3DPointsFromDepthImageInto() storing the projected 3D points (wit...
mrpt::utils::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...