Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
This kind of observations can carry one or more of these data fields:
The coordinates of the 3D point cloud are in meters with respect to the depth camera origin of coordinates (in SwissRanger, the front face of the camera: a small offset ~1cm in front of the physical focal point), with the +X axis pointing forward, +Y pointing left-hand and +Z pointing up. By convention, a 3D point with its coordinates set to (0,0,0), will be considered as invalid. The field CObservation3DRangeScan::relativePoseIntensityWRTDepth describes the change of coordinates from the depth camera to the intensity (RGB or grayscale) camera. In a SwissRanger camera both cameras coincide, so this pose is just a rotation (0,0,0,-90deg,0,-90deg). But in Microsoft Kinect there is also an offset, as shown in this figure:
In any case, check the field relativePoseIntensityWRTDepth, or the method doDepthAndIntensityCamerasCoincide() to determine if both frames of reference coincide, since even for Kinect cameras both can coincide if the images have been rectified.
The 2D images and matrices are stored as common images, with an up->down rows order and left->right, as usual. Optionally, the intensity and confidence channels can be set to delayed-load images for off-rawlog storage so it saves memory by having loaded in memory just the needed images. See the methods load() and unload(). Due to the intensive storage requirements of this kind of observations, this observation is the only one in MRPT for which it's recommended to always call "load()" and "unload()" before and after using the observation, ONLY when the observation was read from a rawlog dataset, in order to make sure that all the externally stored data fields are loaded and ready in memory.
Classes that grab observations of this type are:
There are two sets of calibration parameters (see mrpt::vision::checkerBoardStereoCalibration() or the ready-to-use GUI program kinect-calibrate):
In some cameras, like SwissRanger, both are the same. It is possible in Kinect to rectify the range images such both cameras seem to coincide and then both sets of camera parameters will be identical.
Range data can be interpreted in two different ways depending on the 3D camera (this field is already set to the correct setting when grabbing observations from an mrpt::hwdrivers sensor):
The "intensity" channel may come from different channels in sesnsors as Kinect. Look at field intensityImageChannel to find out if the image was grabbed from the visible (RGB) or IR channels.
3D point clouds can be generated at any moment after grabbing with CObservation3DRangeScan::project3DPointsFromDepthImage() and CObservation3DRangeScan::project3DPointsFromDepthImageInto(), provided the correct calibration parameters. Note that project3DPointsFromDepthImage() will store the point cloud in sensor-centric local coordinates. Use project3DPointsFromDepthImageInto() to directly obtain vehicle or world coordinates.
Example of how to assign labels to pixels (for object segmentation, semantic information, etc.):
CObservation3DRangeScan::EXTERNALS_AS_TEXT
Definition at line 145 of file obs/CObservation3DRangeScan.h.
#include <mrpt/obs/CObservation3DRangeScan.h>
Classes | |
struct | TCached3DProjTables |
Look-up-table struct for project3DPointsFromDepthImageInto() More... | |
struct | TPixelLabelInfo |
struct | TPixelLabelInfoBase |
Virtual interface to all pixel-label information structs. More... | |
Public Member Functions | |
void * | operator new (size_t size) |
void * | operator new[] (size_t size) |
void | operator delete (void *ptr) throw () |
void | operator delete[] (void *ptr) throw () |
void | operator delete (void *memory, void *ptr) throw () |
void * | operator new (size_t size, const std::nothrow_t &) throw () |
void | operator delete (void *ptr, const std::nothrow_t &) throw () |
CObservation3DRangeScan () | |
Default constructor. More... | |
virtual | ~CObservation3DRangeScan () |
Destructor. More... | |
template<class POINTMAP > | |
void | project3DPointsFromDepthImageInto (POINTMAP &dest_pointcloud, const T3DPointsProjectionParams &projectParams, const TRangeImageFilterParams &filterParams=TRangeImageFilterParams()) |
Project the RGB+D images into a 3D point cloud (with color if the target map supports it) and optionally at a given 3D pose. More... | |
template<class POINTMAP > | |
void | project3DPointsFromDepthImageInto (POINTMAP &dest_pointcloud, const bool takeIntoAccountSensorPoseOnRobot, const mrpt::poses::CPose3D *robotPoseInTheWorld=NULL, const bool PROJ3D_USE_LUT=true, const mrpt::math::CMatrix *rangeMask_min=NULL) |
void | project3DPointsFromDepthImage (const bool PROJ3D_USE_LUT=true) |
This method is equivalent to project3DPointsFromDepthImageInto() storing the projected 3D points (without color, in local sensor-centric coordinates) in this same class. More... | |
void | convertTo2DScan (mrpt::obs::CObservation2DRangeScan &out_scan2d, const T3DPointsTo2DScanParams &scanParams, const TRangeImageFilterParams &filterParams=TRangeImageFilterParams()) |
Convert this 3D observation into an "equivalent 2D fake laser scan", with a configurable vertical FOV. More... | |
void | convertTo2DScan (mrpt::obs::CObservation2DRangeScan &out_scan2d, const std::string &sensorLabel, const double angle_sup=mrpt::utils::DEG2RAD(5), const double angle_inf=mrpt::utils::DEG2RAD(5), const double oversampling_ratio=1.2, const mrpt::math::CMatrix *rangeMask_min=NULL) |
void | getDescriptionAsText (std::ostream &o) const MRPT_OVERRIDE |
Build a detailed, multi-line textual description of the observation contents and dump it to the output stream. More... | |
void | swap (CObservation3DRangeScan &o) |
Very efficient method to swap the contents of two observations. More... | |
void | getZoneAsObs (CObservation3DRangeScan &obs, const unsigned int &r1, const unsigned int &r2, const unsigned int &c1, const unsigned int &c2) |
Extract a ROI of the 3D observation as a new one. More... | |
template<class METRICMAP > | |
bool | insertObservationInto (METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose=NULL) const |
This method is equivalent to: More... | |
void | getSensorPose (mrpt::math::TPose3D &out_sensorPose) const |
A general method to retrieve the sensor pose on the robot. More... | |
void | setSensorPose (const mrpt::math::TPose3D &newSensorPose) |
A general method to change the sensor pose on the robot. More... | |
virtual mxArray * | writeToMatlab () const |
Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More... | |
CObject * | clone () const |
Cloning interface for smart pointers. More... | |
Delayed-load manual control methods. | |
virtual void | load () const MRPT_OVERRIDE |
Makes sure all images and other fields which may be externally stored are loaded in memory. More... | |
virtual void | unload () MRPT_OVERRIDE |
Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect). More... | |
Point cloud external storage functions | |
bool | points3D_isExternallyStored () const |
std::string | points3D_getExternalStorageFile () const |
void | points3D_getExternalStorageFileAbsolutePath (std::string &out_path) const |
std::string | points3D_getExternalStorageFileAbsolutePath () const |
void | points3D_convertToExternalStorage (const std::string &fileName, const std::string &use_this_base_dir) |
Users won't normally want to call this, it's only used from internal MRPT programs. More... | |
Range Matrix external storage functions | |
bool | rangeImage_isExternallyStored () const |
std::string | rangeImage_getExternalStorageFile () const |
void | rangeImage_getExternalStorageFileAbsolutePath (std::string &out_path) const |
std::string | rangeImage_getExternalStorageFileAbsolutePath () const |
void | rangeImage_convertToExternalStorage (const std::string &fileName, const std::string &use_this_base_dir) |
Users won't normally want to call this, it's only used from internal MRPT programs. More... | |
void | rangeImage_forceResetExternalStorage () |
Forces marking this observation as non-externally stored - it doesn't anything else apart from reseting the corresponding flag (Users won't normally want to call this, it's only used from internal MRPT programs) More... | |
RTTI classes and functions | |
mrpt::utils::CObjectPtr | duplicateGetSmartPtr () const |
Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More... | |
Static Public Member Functions | |
static void * | operator new (size_t size, void *ptr) |
static double | recoverCameraCalibrationParameters (const CObservation3DRangeScan &in_obs, mrpt::utils::TCamera &out_camParams, const double camera_offset=0.01) |
A Levenberg-Marquart-based optimizer to recover the calibration parameters of a 3D camera given a range (depth) image and the corresponding 3D point cloud. More... | |
Public Attributes | |
Confidence "channel" | |
bool | hasConfidenceImage |
true means the field confidenceImage contains valid data More... | |
mrpt::utils::CImage | confidenceImage |
If hasConfidenceImage=true, an image with the "confidence" value [range 0-255] as estimated by the capture drivers. More... | |
Static Public Attributes | |
static bool | EXTERNALS_AS_TEXT = false |
Whether external files (3D points, range and confidence) are to be saved as .txt text files (MATLAB compatible) or *.bin binary (faster). More... | |
static TCached3DProjTables | m_3dproj_lut |
3D point cloud projection look-up-table More... | |
static const mrpt::utils::TRuntimeClassId | classCObject |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCObservation |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCSerializable |
Protected Member Functions | |
void | swap (CObservation &o) |
Swap with another observation, ONLY the data defined here in the base class CObservation. It's protected since it'll be only called from child classes that should know what else to swap appart from these common data. More... | |
CSerializable virtual methods | |
void | writeToStream (mrpt::utils::CStream &out, int *getVersion) const |
Introduces a pure virtual method responsible for writing to a CStream. More... | |
void | readFromStream (mrpt::utils::CStream &in, int version) |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More... | |
Protected Attributes | |
bool | m_points3D_external_stored |
If set to true, m_points3D_external_file is valid. More... | |
std::string | m_points3D_external_file |
3D points are in CImage::IMAGES_PATH_BASE+<this_file_name> More... | |
bool | m_rangeImage_external_stored |
If set to true, m_rangeImage_external_file is valid. More... | |
std::string | m_rangeImage_external_file |
rangeImage is in CImage::IMAGES_PATH_BASE+<this_file_name> More... | |
Data common to any observation | |
mrpt::system::TTimeStamp | timestamp |
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based timestamp of the sensor reading. More... | |
std::string | sensorLabel |
An arbitrary label that can be used to identify the sensor. More... | |
mrpt::system::TTimeStamp | getTimeStamp () const |
Returns CObservation::timestamp for all kind of observations. More... | |
virtual mrpt::system::TTimeStamp | getOriginalReceivedTimeStamp () const |
By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accurate UTC timing of readings, this contains the computer-based timestamp of reception, which may be slightly different than timestamp. More... | |
RTTI stuff | |
typedef CObservation3DRangeScanPtr | Ptr |
typedef CObservation3DRangeScanPtr | ConstPtr |
static mrpt::utils::CLASSINIT | _init_CObservation3DRangeScan |
static mrpt::utils::TRuntimeClassId | classCObservation3DRangeScan |
static const mrpt::utils::TRuntimeClassId * | classinfo |
static const mrpt::utils::TRuntimeClassId * | _GetBaseClass () |
virtual const mrpt::utils::TRuntimeClassId * | GetRuntimeClass () const |
Returns information about the class of an object in runtime. More... | |
virtual mrpt::utils::CObject * | duplicate () const |
Returns a copy of the object, indepently of its class. More... | |
static mrpt::utils::CObject * | CreateObject () |
static CObservation3DRangeScanPtr | Create () |
Point cloud | |
bool | hasPoints3D |
true means the field points3D contains valid data. More... | |
std::vector< float > | points3D_x |
std::vector< float > | points3D_y |
std::vector< float > | points3D_z |
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera. More... | |
std::vector< uint16_t > | points3D_idxs_x |
std::vector< uint16_t > | points3D_idxs_y |
//!< If hasPoints3D=true, the (x,y) pixel coordinates for each (X,Y,Z) point in points3D_x, points3D_y, points3D_z More... | |
void | resizePoints3DVectors (const size_t nPoints) |
Use this method instead of resizing all three points3D_x, points3D_y & points3D_z to allow the usage of the internal memory pool. More... | |
Range (depth) image | |
bool | hasRangeImage |
true means the field rangeImage contains valid data More... | |
mrpt::math::CMatrix | rangeImage |
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) More... | |
bool | range_is_depth |
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in rangeImage are actual distances in 3D. More... | |
void | rangeImage_setSize (const int HEIGHT, const int WIDTH) |
Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the memory allocation. More... | |
Intensity (RGB) channels | |
enum | TIntensityChannelID { CH_VISIBLE = 0, CH_IR = 1 } |
Enum type for intensityImageChannel. More... | |
bool | hasIntensityImage |
true means the field intensityImage contains valid data More... | |
mrpt::utils::CImage | intensityImage |
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage". More... | |
TIntensityChannelID | intensityImageChannel |
The source of the intensityImage; typically the visible channel. More... | |
Pixel-wise classification labels (for semantic labeling, etc.) | |
typedef std::shared_ptr< TPixelLabelInfoBase > | TPixelLabelInfoPtr |
Used in CObservation3DRangeScan::pixelLabels. More... | |
TPixelLabelInfoPtr | pixelLabels |
All information about pixel labeling is stored in this (smart pointer to) structure; refer to TPixelLabelInfo for details on the contents User is responsible of creating a new object of the desired data type. More... | |
bool | hasPixelLabels () const |
Returns true if the field CObservation3DRangeScan::pixelLabels contains a non-NULL smart pointer. More... | |
Sensor parameters | |
mrpt::utils::TCamera | cameraParams |
Projection parameters of the depth camera. More... | |
mrpt::utils::TCamera | cameraParamsIntensity |
Projection parameters of the intensity (graylevel or RGB) camera. More... | |
mrpt::poses::CPose3D | relativePoseIntensityWRTDepth |
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this observation). More... | |
float | maxRange |
The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...) More... | |
mrpt::poses::CPose3D | sensorPose |
The 6D pose of the sensor on the robot. More... | |
float | stdError |
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid. More... | |
bool | doDepthAndIntensityCamerasCoincide () const |
Return true if relativePoseIntensityWRTDepth equals the pure rotation (0,0,0,-90deg,0,-90deg) (with a small comparison epsilon) More... | |
void | getSensorPose (mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE |
A general method to retrieve the sensor pose on the robot. More... | |
void | setSensorPose (const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE |
A general method to change the sensor pose on the robot. More... | |
typedef CObservation3DRangeScanPtr mrpt::obs::CObservation3DRangeScan::ConstPtr |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
typedef CObservation3DRangeScanPtr mrpt::obs::CObservation3DRangeScan::Ptr |
A typedef for the associated smart pointer
Definition at line 148 of file obs/CObservation3DRangeScan.h.
typedef std::shared_ptr<TPixelLabelInfoBase> mrpt::obs::CObservation3DRangeScan::TPixelLabelInfoPtr |
Used in CObservation3DRangeScan::pixelLabels.
Definition at line 427 of file obs/CObservation3DRangeScan.h.
Enum type for intensityImageChannel.
Enumerator | |
---|---|
CH_VISIBLE | Grayscale or RGB visible channel of the camera sensor. |
CH_IR | Infrarred (IR) channel. |
Definition at line 341 of file obs/CObservation3DRangeScan.h.
CObservation3DRangeScan::CObservation3DRangeScan | ( | ) |
Default constructor.
Definition at line 136 of file CObservation3DRangeScan.cpp.
|
virtual |
Destructor.
Definition at line 159 of file CObservation3DRangeScan.cpp.
References mempool_donate_range_matrix(), and mempool_donate_xyz_buffers().
|
staticprotected |
|
inlineinherited |
void CObservation3DRangeScan::convertTo2DScan | ( | mrpt::obs::CObservation2DRangeScan & | out_scan2d, |
const T3DPointsTo2DScanParams & | scanParams, | ||
const TRangeImageFilterParams & | filterParams = TRangeImageFilterParams() |
||
) |
Convert this 3D observation into an "equivalent 2D fake laser scan", with a configurable vertical FOV.
The result is a 2D laser scan with more "rays" (N) than columns has the 3D observation (W), exactly: N = W * oversampling_ratio. This oversampling is required since laser scans sample the space at evenly-separated angles, while a range camera follows a tangent-like distribution. By oversampling we make sure we don't leave "gaps" unseen by the virtual "2D laser".
All obstacles within a frustum are considered and the minimum distance is kept in each direction. The horizontal FOV of the frustum is automatically computed from the intrinsic parameters, but the vertical FOV must be provided by the user, and can be set to be assymetric which may be useful depending on the zone of interest where to look for obstacles.
All spatial transformations are riguorosly taken into account in this class, using the depth camera intrinsic calibration parameters.
The timestamp of the new object is copied from the 3D object. Obviously, a requisite for calling this method is the 3D observation having range data, i.e. hasRangeImage must be true. It's not needed to have RGB data nor the raw 3D point clouds for this method to work.
If scanParams.use_origin_sensor_pose
is true
, the points will be projected to 3D and then reprojected as seen from a different sensorPose at the vehicle frame origin. Otherwise (the default), the output 2D observation will share the sensorPose of the input 3D scan (using a more efficient algorithm that avoids trigonometric functions).
[out] | out_scan2d | The resulting 2D equivalent scan. |
Definition at line 897 of file CObservation3DRangeScan.cpp.
References mrpt::obs::T3DPointsTo2DScanParams::angle_inf, mrpt::obs::T3DPointsTo2DScanParams::angle_sup, mrpt::obs::CObservation2DRangeScan::aperture, ASSERT_ABOVE_, ASSERT_EQUAL_, cameraParams, mrpt::opengl::CPointCloud::Create(), mrpt::utils::TCamera::cx(), mrpt::utils::TCamera::cy(), mrpt::obs::TRangeImageFilter::do_range_filter(), mrpt::utils::TCamera::fx(), mrpt::utils::TCamera::fy(), hasRangeImage, mrpt::mrpt::utils::keep_min(), mrpt::obs::CObservation2DRangeScan::maxRange, maxRange, min, mrpt::obs::T3DPointsTo2DScanParams::oversampling_ratio, project3DPointsFromDepthImageInto(), rangeImage, mrpt::obs::TRangeImageFilterParams::rangeMask_max, mrpt::obs::TRangeImageFilterParams::rangeMask_min, mrpt::obs::CObservation2DRangeScan::resizeScan(), mrpt::obs::CObservation2DRangeScan::resizeScanAndAssign(), mrpt::obs::CObservation2DRangeScan::rightToLeft, mrpt::obs::CObservation2DRangeScan::scan, mrpt::obs::CObservation::sensorLabel, mrpt::obs::CObservation2DRangeScan::sensorPose, sensorPose, mrpt::obs::CObservation2DRangeScan::setScanRange(), mrpt::obs::CObservation2DRangeScan::setScanRangeValidity(), mrpt::obs::T3DPointsProjectionParams::takeIntoAccountSensorPoseOnRobot, mrpt::obs::CObservation::timestamp, mrpt::obs::T3DPointsTo2DScanParams::use_origin_sensor_pose, mrpt::obs::T3DPointsTo2DScanParams::z_max, and mrpt::obs::T3DPointsTo2DScanParams::z_min.
Referenced by convertTo2DScan().
void CObservation3DRangeScan::convertTo2DScan | ( | mrpt::obs::CObservation2DRangeScan & | out_scan2d, |
const std::string & | sensorLabel, | ||
const double | angle_sup = mrpt::utils::DEG2RAD(5) , |
||
const double | angle_inf = mrpt::utils::DEG2RAD(5) , |
||
const double | oversampling_ratio = 1.2 , |
||
const mrpt::math::CMatrix * | rangeMask_min = NULL |
||
) |
Definition at line 878 of file CObservation3DRangeScan.cpp.
References mrpt::obs::T3DPointsTo2DScanParams::angle_inf, mrpt::obs::T3DPointsTo2DScanParams::angle_sup, convertTo2DScan(), mrpt::obs::T3DPointsTo2DScanParams::oversampling_ratio, mrpt::obs::TRangeImageFilterParams::rangeMask_min, mrpt::obs::T3DPointsTo2DScanParams::sensorLabel, and mrpt::obs::CObservation::sensorLabel.
|
static |
|
static |
bool CObservation3DRangeScan::doDepthAndIntensityCamerasCoincide | ( | ) | const |
Return true if relativePoseIntensityWRTDepth equals the pure rotation (0,0,0,-90deg,0,-90deg) (with a small comparison epsilon)
Definition at line 866 of file CObservation3DRangeScan.cpp.
References DEG2RAD, mrpt::poses::CPose3D::getRotationMatrix(), mrpt::poses::CPose3D::m_coords, and relativePoseIntensityWRTDepth.
Referenced by mrpt::obs::detail::project3DPointsFromDepthImageInto().
|
virtual |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
|
inlineinherited |
Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer).
Definition at line 162 of file CObject.h.
References mrpt::utils::CObjectPtr.
Referenced by mrpt::obs::CRawlog::addActions(), mrpt::slam::CIncrementalMapPartitioner::addMapFrame(), and mrpt::obs::CRawlog::addObservations().
|
virtual |
Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
Reimplemented from mrpt::obs::CObservation.
Definition at line 1046 of file CObservation3DRangeScan.cpp.
References cameraParams, cameraParamsIntensity, confidenceImage, mrpt::utils::CConfigFileMemory::getContent(), mrpt::obs::CObservation::getDescriptionAsText(), mrpt::utils::CImage::getExternalStorageFile(), mrpt::poses::CPose3D::getHomogeneousMatrixVal(), hasConfidenceImage, hasIntensityImage, hasPixelLabels(), hasPoints3D, hasRangeImage, intensityImage, intensityImageChannel, mrpt::utils::CImage::isExternallyStored(), load(), maxRange, pixelLabels, points3D_getExternalStorageFile(), points3D_isExternallyStored(), points3D_x, rangeImage_getExternalStorageFile(), rangeImage_isExternallyStored(), relativePoseIntensityWRTDepth, mrpt::utils::TCamera::saveToConfigFile(), sensorPose, and mrpt::utils::TEnumType< ENUMTYPE >::value2name().
|
inlinevirtualinherited |
By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accurate UTC timing of readings, this contains the computer-based timestamp of reception, which may be slightly different than timestamp.
Reimplemented in mrpt::obs::CObservationGPS, and mrpt::obs::CObservationVelodyneScan.
Definition at line 58 of file obs/CObservation.h.
|
virtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::obs::CObservation.
|
inherited |
A general method to retrieve the sensor pose on the robot.
Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.
Definition at line 38 of file CObservation.cpp.
|
inlinevirtual |
A general method to retrieve the sensor pose on the robot.
Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.
Implements mrpt::obs::CObservation.
Definition at line 550 of file obs/CObservation3DRangeScan.h.
|
inlineinherited |
Returns CObservation::timestamp for all kind of observations.
Definition at line 56 of file obs/CObservation.h.
void CObservation3DRangeScan::getZoneAsObs | ( | CObservation3DRangeScan & | obs, |
const unsigned int & | r1, | ||
const unsigned int & | r2, | ||
const unsigned int & | c1, | ||
const unsigned int & | c2 | ||
) |
Extract a ROI of the 3D observation as a new one.
Definition at line 724 of file CObservation3DRangeScan.cpp.
References ASSERT_, cameraParams, confidenceImage, mrpt::utils::CImage::extract_patch(), hasConfidenceImage, hasIntensityImage, hasPoints3D, hasRangeImage, intensityImage, intensityImageChannel, maxRange, mrpt::utils::TCamera::ncols, mrpt::utils::TCamera::nrows, points3D_x, points3D_y, points3D_z, rangeImage, sensorPose, and stdError.
Referenced by mrpt::detectors::CFaceDetection::detectObjects_Impl().
|
inline |
Returns true if the field CObservation3DRangeScan::pixelLabels contains a non-NULL smart pointer.
To enhance a 3D point cloud with labeling info, just assign an appropiate object to pixelLabels
Definition at line 363 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), and writeToStream().
|
inlineinherited |
This method is equivalent to:
theMap | The map where this observation is to be inserted: the map will be updated. |
robotPose | The pose of the robot base for this observation, relative to the target metric map. Set to NULL (default) to use (0,0,0deg) |
See: Maps and observations compatibility matrix
Definition at line 77 of file obs/CObservation.h.
Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference().
|
virtual |
Makes sure all images and other fields which may be externally stored are loaded in memory.
Note that for all CImages, calling load() is not required since the images will be automatically loaded upon first access, so load() shouldn't be needed to be called in normal cases by the user. If all the data were alredy loaded or this object has no externally stored data fields, calling this method has no effects.
Reimplemented from mrpt::obs::CObservation.
Definition at line 408 of file CObservation3DRangeScan.cpp.
References ASSERT_EQUAL_, mrpt::system::extractFileExtension(), hasPoints3D, hasRangeImage, loadFromTextFile(), m_points3D_external_stored, m_rangeImage_external_stored, points3D_getExternalStorageFileAbsolutePath(), points3D_x, points3D_y, points3D_z, rangeImage, rangeImage_getExternalStorageFileAbsolutePath(), and mrpt::system::strCmpI().
Referenced by getDescriptionAsText(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), and mrpt::maps::CColouredOctoMap::internal_insertObservation().
Definition at line 148 of file obs/CObservation3DRangeScan.h.
|
inline |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
|
inline |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
Definition at line 148 of file obs/CObservation3DRangeScan.h.
|
inlinestatic |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
|
inline |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
|
inline |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
|
inline |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
void CObservation3DRangeScan::points3D_convertToExternalStorage | ( | const std::string & | fileName, |
const std::string & | use_this_base_dir | ||
) |
Users won't normally want to call this, it's only used from internal MRPT programs.
Definition at line 494 of file CObservation3DRangeScan.cpp.
References ASSERT_, CFileGZOutputStream, EXTERNALS_AS_TEXT, mrpt::system::fileNameChangeExtension(), m_points3D_external_file, m_points3D_external_stored, mrpt::math::MATRIX_FORMAT_FIXED, points3D_getExternalStorageFileAbsolutePath(), points3D_idxs_x, points3D_idxs_y, points3D_isExternallyStored(), points3D_x, points3D_y, points3D_z, and mrpt::utils::vector_strong_clear().
|
inline |
Definition at line 303 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText().
void CObservation3DRangeScan::points3D_getExternalStorageFileAbsolutePath | ( | std::string & | out_path | ) | const |
Definition at line 477 of file CObservation3DRangeScan.cpp.
References ASSERT_, and m_points3D_external_file.
|
inline |
Definition at line 305 of file obs/CObservation3DRangeScan.h.
Referenced by load(), and points3D_convertToExternalStorage().
|
inline |
Definition at line 302 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), and points3D_convertToExternalStorage().
|
inline |
This method is equivalent to project3DPointsFromDepthImageInto()
storing the projected 3D points (without color, in local sensor-centric coordinates) in this same class.
For new code it's recommended to use instead project3DPointsFromDepthImageInto()
which is much more versatile.
Definition at line 237 of file obs/CObservation3DRangeScan.h.
References mrpt::obs::detail::project3DPointsFromDepthImageInto().
Referenced by mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), and mrpt::hwdrivers::CKinect::getNextObservation().
|
inline |
Project the RGB+D images into a 3D point cloud (with color if the target map supports it) and optionally at a given 3D pose.
The 3D point coordinates are computed from the depth image (rangeImage) and the depth camera camera parameters (cameraParams). There exist two set of formulas for projecting the i'th point, depending on the value of "range_is_depth". In all formulas below, "rangeImage" is the matrix of ranges and the pixel coordinates are (r,c).
1) [range_is_depth=true] With "range equals depth" or "Kinect-like depth mode": the range values are in fact distances along the "+X" axis, not real 3D ranges (this is the way Kinect reports ranges):
2) [range_is_depth=false] With "normal ranges": range means distance in 3D. This must be set when processing data from the SwissRange 3D camera, among others.
The color of each point is determined by projecting the 3D local point into the RGB image using cameraParamsIntensity.
By default the local (sensor-centric) coordinates of points are directly stored into the local map, but if indicated so in takeIntoAccountSensorPoseOnRobot the points are transformed with sensorPose. Furthermore, if provided, those coordinates are transformed with robotPoseInTheWorld
POINTMAP | Supported maps are all those covered by mrpt::utils::PointCloudAdapter (mrpt::maps::CPointsMap and derived, mrpt::opengl::CPointCloudColoured, PCL point clouds,...) |
Definition at line 212 of file obs/CObservation3DRangeScan.h.
Referenced by convertTo2DScan(), and TEST().
|
inline |
Definition at line 218 of file obs/CObservation3DRangeScan.h.
References mrpt::obs::T3DPointsProjectionParams::PROJ3D_USE_LUT, mrpt::obs::TRangeImageFilterParams::rangeMask_min, mrpt::obs::T3DPointsProjectionParams::robotPoseInTheWorld, and mrpt::obs::T3DPointsProjectionParams::takeIntoAccountSensorPoseOnRobot.
void CObservation3DRangeScan::rangeImage_convertToExternalStorage | ( | const std::string & | fileName, |
const std::string & | use_this_base_dir | ||
) |
Users won't normally want to call this, it's only used from internal MRPT programs.
Definition at line 537 of file CObservation3DRangeScan.cpp.
References ASSERT_, CFileGZOutputStream, EXTERNALS_AS_TEXT, mrpt::system::fileNameChangeExtension(), m_rangeImage_external_file, m_rangeImage_external_stored, mrpt::math::MATRIX_FORMAT_FIXED, rangeImage, rangeImage_getExternalStorageFileAbsolutePath(), and rangeImage_isExternallyStored().
|
inline |
Forces marking this observation as non-externally stored - it doesn't anything else apart from reseting the corresponding flag (Users won't normally want to call this, it's only used from internal MRPT programs)
Definition at line 334 of file obs/CObservation3DRangeScan.h.
|
inline |
Definition at line 325 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText().
void CObservation3DRangeScan::rangeImage_getExternalStorageFileAbsolutePath | ( | std::string & | out_path | ) | const |
Definition at line 461 of file CObservation3DRangeScan.cpp.
References ASSERT_, and m_rangeImage_external_file.
|
inline |
Definition at line 327 of file obs/CObservation3DRangeScan.h.
Referenced by load(), and rangeImage_convertToExternalStorage().
|
inline |
Definition at line 324 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), and rangeImage_convertToExternalStorage().
void CObservation3DRangeScan::rangeImage_setSize | ( | const int | HEIGHT, |
const int | WIDTH | ||
) |
Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the memory allocation.
Definition at line 839 of file CObservation3DRangeScan.cpp.
References mrpt::system::CGenericMemoryPool< DATA_PARAMS, POOLABLE_DATA >::getInstance(), CObservation3DRangeScan_Ranges_MemPoolParams::H, CObservation3DRangeScan_Ranges_MemPoolData::rangeImage, rangeImage, mrpt::system::CGenericMemoryPool< DATA_PARAMS, POOLABLE_DATA >::request_memory(), and CObservation3DRangeScan_Ranges_MemPoolParams::W.
Referenced by fillSampleObs(), and readFromStream().
|
protectedvirtual |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.
in | The input binary stream where the object data must read from. |
version | The version of the object stored in the stream: use this version number in your code to know how to read the incoming data. |
std::exception | On any error, see CStream::ReadBuffer |
Implements mrpt::utils::CSerializable.
Definition at line 229 of file CObservation3DRangeScan.cpp.
References cameraParams, cameraParamsIntensity, CH_VISIBLE, confidenceImage, hasConfidenceImage, hasIntensityImage, hasPoints3D, hasRangeImage, intensityImage, intensityImageChannel, m_points3D_external_file, m_points3D_external_stored, m_rangeImage_external_file, m_rangeImage_external_stored, maxRange, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, pixelLabels, points3D_idxs_x, points3D_idxs_y, points3D_x, points3D_y, points3D_z, range_is_depth, rangeImage, rangeImage_setSize(), mrpt::obs::CObservation3DRangeScan::TPixelLabelInfoBase::readAndBuildFromStream(), relativePoseIntensityWRTDepth, resizePoints3DVectors(), mrpt::obs::CObservation::sensorLabel, sensorPose, stdError, mrpt::obs::CObservation::timestamp, and version.
|
static |
A Levenberg-Marquart-based optimizer to recover the calibration parameters of a 3D camera given a range (depth) image and the corresponding 3D point cloud.
camera_offset | The offset (in meters) in the +X direction of the point cloud. It's 1cm for SwissRanger SR4000. |
Definition at line 663 of file CObservation3DRangeScan.cpp.
References ASSERT_, CALIB_DECIMAT, mrpt::obs::detail::cam2vec(), mrpt::obs::detail::cost_func(), mrpt::utils::TCamera::focalLengthMeters, hasPoints3D, hasRangeImage, info, mrpt::utils::TCamera::intrinsicParams, MRPT_END, MRPT_START, mrpt::utils::TCamera::ncols, mrpt::utils::TCamera::nrows, points3D_x, points3D_y, points3D_z, rangeImage, mrpt::math::square(), and mrpt::obs::detail::vec2cam().
void CObservation3DRangeScan::resizePoints3DVectors | ( | const size_t | WH | ) |
Use this method instead of resizing all three points3D_x, points3D_y & points3D_z to allow the usage of the internal memory pool.
Definition at line 785 of file CObservation3DRangeScan.cpp.
References mrpt::system::CGenericMemoryPool< DATA_PARAMS, POOLABLE_DATA >::getInstance(), CObservation3DRangeScan_Points_MemPoolData::idxs_x, CObservation3DRangeScan_Points_MemPoolData::idxs_y, points3D_idxs_x, points3D_idxs_y, points3D_x, points3D_y, points3D_z, CObservation3DRangeScan_Points_MemPoolData::pts_x, CObservation3DRangeScan_Points_MemPoolData::pts_y, CObservation3DRangeScan_Points_MemPoolData::pts_z, mrpt::system::CGenericMemoryPool< DATA_PARAMS, POOLABLE_DATA >::request_memory(), mrpt::utils::vector_strong_clear(), and CObservation3DRangeScan_Points_MemPoolParams::WH.
Referenced by mrpt::obs::detail::project3DPointsFromDepthImageInto(), readFromStream(), and mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::resize().
|
inherited |
A general method to change the sensor pose on the robot.
Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.
Definition at line 45 of file CObservation.cpp.
|
inlinevirtual |
A general method to change the sensor pose on the robot.
Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.
Implements mrpt::obs::CObservation.
Definition at line 552 of file obs/CObservation3DRangeScan.h.
|
protectedinherited |
Swap with another observation, ONLY the data defined here in the base class CObservation. It's protected since it'll be only called from child classes that should know what else to swap appart from these common data.
Definition at line 50 of file CObservation.cpp.
References mrpt::obs::CObservation::sensorLabel, and mrpt::obs::CObservation::timestamp.
Referenced by mrpt::obs::CObservationStereoImages::swap(), and swap().
void CObservation3DRangeScan::swap | ( | CObservation3DRangeScan & | o | ) |
Very efficient method to swap the contents of two observations.
Definition at line 370 of file CObservation3DRangeScan.cpp.
References cameraParams, cameraParamsIntensity, confidenceImage, hasConfidenceImage, hasIntensityImage, hasPoints3D, hasRangeImage, intensityImage, intensityImageChannel, m_points3D_external_file, m_points3D_external_stored, m_rangeImage_external_file, m_rangeImage_external_stored, maxRange, pixelLabels, points3D_idxs_x, points3D_idxs_y, points3D_x, points3D_y, points3D_z, rangeImage, relativePoseIntensityWRTDepth, sensorPose, stdError, mrpt::obs::CObservation::swap(), and mrpt::utils::CImage::swap().
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), and mrpt::hwdrivers::CKinect::getNextObservation().
|
virtual |
Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).
Reimplemented from mrpt::obs::CObservation.
Definition at line 445 of file CObservation3DRangeScan.cpp.
References confidenceImage, hasPoints3D, hasRangeImage, intensityImage, m_points3D_external_stored, m_rangeImage_external_stored, points3D_x, points3D_y, points3D_z, rangeImage, mrpt::utils::CImage::unload(), and mrpt::utils::vector_strong_clear().
|
inlinevirtualinherited |
Introduces a pure virtual method responsible for writing to a mxArray
Matlab object, typically a MATLAB struct
whose contents are documented in each derived class.
mxArray
(caller is responsible of memory freeing) or NULL is class does not support conversion to MATLAB. Definition at line 79 of file CSerializable.h.
|
protectedvirtual |
Introduces a pure virtual method responsible for writing to a CStream.
This can not be used directly be users, instead use "stream << object;" for writing it to a stream.
out | The output binary stream where object must be dumped. |
getVersion | If NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data. |
std::exception | On any error, see CStream::WriteBuffer |
Implements mrpt::utils::CSerializable.
Definition at line 170 of file CObservation3DRangeScan.cpp.
References ASSERT_, cameraParams, cameraParamsIntensity, confidenceImage, hasConfidenceImage, hasIntensityImage, hasPixelLabels(), hasPoints3D, hasRangeImage, intensityImage, intensityImageChannel, m_points3D_external_file, m_points3D_external_stored, m_rangeImage_external_file, m_rangeImage_external_stored, maxRange, pixelLabels, points3D_idxs_x, points3D_idxs_y, points3D_x, points3D_y, points3D_z, range_is_depth, rangeImage, relativePoseIntensityWRTDepth, mrpt::obs::CObservation::sensorLabel, sensorPose, stdError, mrpt::obs::CObservation::timestamp, version, and mrpt::utils::CStream::WriteBufferFixEndianness().
|
staticprotected |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
mrpt::utils::TCamera mrpt::obs::CObservation3DRangeScan::cameraParams |
Projection parameters of the depth camera.
Definition at line 530 of file obs/CObservation3DRangeScan.h.
Referenced by convertTo2DScan(), getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), getZoneAsObs(), mrpt::obs::detail::range2XYZ(), mrpt::obs::detail::range2XYZ_LUT(), readFromStream(), swap(), and writeToStream().
mrpt::utils::TCamera mrpt::obs::CObservation3DRangeScan::cameraParamsIntensity |
Projection parameters of the intensity (graylevel or RGB) camera.
Definition at line 531 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_init(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), readFromStream(), swap(), and writeToStream().
|
staticinherited |
|
staticinherited |
Definition at line 43 of file obs/CObservation.h.
|
static |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
|
staticinherited |
Definition at line 42 of file CSerializable.h.
|
static |
Definition at line 148 of file obs/CObservation3DRangeScan.h.
mrpt::utils::CImage mrpt::obs::CObservation3DRangeScan::confidenceImage |
If hasConfidenceImage=true, an image with the "confidence" value [range 0-255] as estimated by the capture drivers.
Definition at line 355 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), getZoneAsObs(), readFromStream(), swap(), unload(), and writeToStream().
|
static |
Whether external files (3D points, range and confidence) are to be saved as .txt
text files (MATLAB compatible) or *.bin
binary (faster).
Loading always will determine the type by inspecting the file extension.
Definition at line 288 of file obs/CObservation3DRangeScan.h.
Referenced by points3D_convertToExternalStorage(), and rangeImage_convertToExternalStorage().
bool mrpt::obs::CObservation3DRangeScan::hasConfidenceImage |
true means the field confidenceImage contains valid data
Definition at line 354 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), getZoneAsObs(), readFromStream(), swap(), and writeToStream().
bool mrpt::obs::CObservation3DRangeScan::hasIntensityImage |
true means the field intensityImage contains valid data
Definition at line 347 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), getZoneAsObs(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_init(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), readFromStream(), swap(), and writeToStream().
bool mrpt::obs::CObservation3DRangeScan::hasPoints3D |
true means the field points3D contains valid data.
Definition at line 292 of file obs/CObservation3DRangeScan.h.
Referenced by mrpt::detectors::CFaceDetection::detectObjects_Impl(), getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), getZoneAsObs(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), load(), readFromStream(), recoverCameraCalibrationParameters(), mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::resize(), swap(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), unload(), and writeToStream().
bool mrpt::obs::CObservation3DRangeScan::hasRangeImage |
true means the field rangeImage contains valid data
Definition at line 315 of file obs/CObservation3DRangeScan.h.
Referenced by convertTo2DScan(), fillSampleObs(), getDescriptionAsText(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::getICPEdge(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), getZoneAsObs(), load(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), readFromStream(), recoverCameraCalibrationParameters(), swap(), unload(), and writeToStream().
mrpt::utils::CImage mrpt::obs::CObservation3DRangeScan::intensityImage |
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
Definition at line 348 of file obs/CObservation3DRangeScan.h.
Referenced by mrpt::detectors::CCascadeClassifierDetection::detectObjects_Impl(), getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), getZoneAsObs(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_init(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), readFromStream(), swap(), unload(), and writeToStream().
TIntensityChannelID mrpt::obs::CObservation3DRangeScan::intensityImageChannel |
The source of the intensityImage; typically the visible channel.
Definition at line 349 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), getZoneAsObs(), readFromStream(), swap(), and writeToStream().
|
static |
3D point cloud projection look-up-table
Definition at line 578 of file obs/CObservation3DRangeScan.h.
Referenced by mrpt::obs::detail::range2XYZ_LUT().
|
protected |
3D points are in CImage::IMAGES_PATH_BASE+<this_file_name>
Definition at line 152 of file obs/CObservation3DRangeScan.h.
Referenced by points3D_convertToExternalStorage(), points3D_getExternalStorageFileAbsolutePath(), readFromStream(), swap(), and writeToStream().
|
protected |
If set to true, m_points3D_external_file is valid.
Definition at line 151 of file obs/CObservation3DRangeScan.h.
Referenced by load(), points3D_convertToExternalStorage(), readFromStream(), swap(), unload(), and writeToStream().
|
protected |
rangeImage is in CImage::IMAGES_PATH_BASE+<this_file_name>
Definition at line 155 of file obs/CObservation3DRangeScan.h.
Referenced by rangeImage_convertToExternalStorage(), rangeImage_getExternalStorageFileAbsolutePath(), readFromStream(), swap(), and writeToStream().
|
protected |
If set to true, m_rangeImage_external_file is valid.
Definition at line 154 of file obs/CObservation3DRangeScan.h.
Referenced by load(), rangeImage_convertToExternalStorage(), readFromStream(), swap(), unload(), and writeToStream().
float mrpt::obs::CObservation3DRangeScan::maxRange |
The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...)
Definition at line 545 of file obs/CObservation3DRangeScan.h.
Referenced by convertTo2DScan(), getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), getZoneAsObs(), readFromStream(), swap(), and writeToStream().
TPixelLabelInfoPtr mrpt::obs::CObservation3DRangeScan::pixelLabels |
All information about pixel labeling is stored in this (smart pointer to) structure; refer to TPixelLabelInfo for details on the contents User is responsible of creating a new object of the desired data type.
It will be automatically (de)serialized no matter its specific type.
Definition at line 524 of file obs/CObservation3DRangeScan.h.
Referenced by getDescriptionAsText(), readFromStream(), swap(), and writeToStream().
std::vector<uint16_t> mrpt::obs::CObservation3DRangeScan::points3D_idxs_x |
Definition at line 294 of file obs/CObservation3DRangeScan.h.
Referenced by mempool_donate_xyz_buffers(), points3D_convertToExternalStorage(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), mrpt::obs::detail::range2XYZ(), mrpt::obs::detail::range2XYZ_LUT(), readFromStream(), resizePoints3DVectors(), swap(), and writeToStream().
std::vector<uint16_t> mrpt::obs::CObservation3DRangeScan::points3D_idxs_y |
//!< If hasPoints3D=true, the (x,y) pixel coordinates for each (X,Y,Z) point in points3D_x, points3D_y, points3D_z
Definition at line 294 of file obs/CObservation3DRangeScan.h.
Referenced by mempool_donate_xyz_buffers(), points3D_convertToExternalStorage(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), mrpt::obs::detail::range2XYZ(), mrpt::obs::detail::range2XYZ_LUT(), readFromStream(), resizePoints3DVectors(), swap(), and writeToStream().
std::vector<float> mrpt::obs::CObservation3DRangeScan::points3D_x |
Definition at line 293 of file obs/CObservation3DRangeScan.h.
Referenced by mrpt::obs::detail::cost_func(), getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::getPointXYZ(), getZoneAsObs(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_init(), load(), mempool_donate_xyz_buffers(), points3D_convertToExternalStorage(), readFromStream(), recoverCameraCalibrationParameters(), resizePoints3DVectors(), mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::setPointXYZ(), mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::size(), swap(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), TEST(), unload(), and writeToStream().
std::vector<float> mrpt::obs::CObservation3DRangeScan::points3D_y |
Definition at line 293 of file obs/CObservation3DRangeScan.h.
Referenced by mrpt::obs::detail::cost_func(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::getPointXYZ(), getZoneAsObs(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), load(), mempool_donate_xyz_buffers(), points3D_convertToExternalStorage(), readFromStream(), recoverCameraCalibrationParameters(), resizePoints3DVectors(), mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::setPointXYZ(), swap(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), unload(), and writeToStream().
std::vector<float> mrpt::obs::CObservation3DRangeScan::points3D_z |
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera.
Definition at line 293 of file obs/CObservation3DRangeScan.h.
Referenced by mrpt::obs::detail::cost_func(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::getPointXYZ(), getZoneAsObs(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), load(), mempool_donate_xyz_buffers(), points3D_convertToExternalStorage(), readFromStream(), recoverCameraCalibrationParameters(), resizePoints3DVectors(), mrpt::utils::PointCloudAdapter< mrpt::obs::CObservation3DRangeScan >::setPointXYZ(), swap(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), unload(), and writeToStream().
bool mrpt::obs::CObservation3DRangeScan::range_is_depth |
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in rangeImage are actual distances in 3D.
Definition at line 317 of file obs/CObservation3DRangeScan.h.
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), readFromStream(), and writeToStream().
mrpt::math::CMatrix mrpt::obs::CObservation3DRangeScan::rangeImage |
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters)
Definition at line 316 of file obs/CObservation3DRangeScan.h.
Referenced by convertTo2DScan(), mrpt::obs::detail::cost_func(), mrpt::detectors::CFaceDetection::experimental_segmentFace(), fillSampleObs(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), getZoneAsObs(), load(), mempool_donate_range_matrix(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), mrpt::obs::detail::range2XYZ(), mrpt::obs::detail::range2XYZ_LUT(), rangeImage_convertToExternalStorage(), rangeImage_setSize(), readFromStream(), recoverCameraCalibrationParameters(), swap(), unload(), and writeToStream().
mrpt::poses::CPose3D mrpt::obs::CObservation3DRangeScan::relativePoseIntensityWRTDepth |
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this observation).
In a SwissRanger camera, this will be (0,0,0,-90deg,0,-90deg) since both cameras coincide. In a Kinect, this will include a small lateral displacement and a rotation, according to the drawing on the top of this page.
Definition at line 538 of file obs/CObservation3DRangeScan.h.
Referenced by doDepthAndIntensityCamerasCoincide(), getDescriptionAsText(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_init(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), readFromStream(), swap(), and writeToStream().
|
inherited |
An arbitrary label that can be used to identify the sensor.
Definition at line 53 of file obs/CObservation.h.
Referenced by mrpt::obs::carmen_log_parse_line(), convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CImpinjRFID::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::obs::CObservation6DFeatures::readFromStream(), mrpt::obs::CObservationStereoImages::readFromStream(), mrpt::obs::CObservation2DRangeScan::readFromStream(), mrpt::obs::CObservationVelodyneScan::readFromStream(), readFromStream(), mrpt::obs::CObservation::swap(), mrpt::obs::CObservationGPS::swap(), mrpt::obs::CObservation6DFeatures::writeToStream(), mrpt::obs::CObservationStereoImages::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), and writeToStream().
mrpt::poses::CPose3D mrpt::obs::CObservation3DRangeScan::sensorPose |
The 6D pose of the sensor on the robot.
Definition at line 546 of file obs/CObservation3DRangeScan.h.
Referenced by convertTo2DScan(), getDescriptionAsText(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), getZoneAsObs(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::obs::detail::project3DPointsFromDepthImageInto(), readFromStream(), swap(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), and writeToStream().
float mrpt::obs::CObservation3DRangeScan::stdError |
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
Definition at line 547 of file obs/CObservation3DRangeScan.h.
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), getZoneAsObs(), readFromStream(), swap(), and writeToStream().
|
inherited |
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based timestamp of the sensor reading.
Definition at line 52 of file obs/CObservation.h.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservationVelodyneScan::TPointCloud::clear_deep(), convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::detectors::CObjectDetection::detectObjects(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::obs::CObservationGasSensors::CMOSmodel::get_GasDistribution_estimation(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::obs::CObservationGasSensors::CMOSmodel::inverse_MOSmodeling(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::obs::CObservationGasSensors::CMOSmodel::noise_filtering(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::obs::CObservation6DFeatures::readFromStream(), mrpt::obs::CObservationStereoImages::readFromStream(), mrpt::obs::CObservation2DRangeScan::readFromStream(), mrpt::obs::CObservationVelodyneScan::readFromStream(), readFromStream(), mrpt::obs::CObservationGasSensors::CMOSmodel::save_log_map(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::obs::CObservation::swap(), mrpt::obs::CObservationGPS::swap(), velodyne_scan_to_pointcloud(), mrpt::obs::CObservation6DFeatures::writeToStream(), mrpt::obs::CObservationStereoImages::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), and writeToStream().
Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019 |