Go to the documentation of this file.
38 void CColouredPointsMap::TMapDefinition::loadFromConfigFile_map_specific(
42 source, sectionNamePrefix +
string(
"_insertOpts"));
43 likelihoodOpts.loadFromConfigFile(
44 source, sectionNamePrefix +
string(
"_likelihoodOpts"));
45 colourOpts.loadFromConfigFile(
46 source, sectionNamePrefix +
string(
"_colorOpts"));
49 void CColouredPointsMap::TMapDefinition::dumpToTextStream_map_specific(
50 std::ostream& out)
const
52 this->insertionOpts.dumpToTextStream(out);
53 this->likelihoodOpts.dumpToTextStream(out);
54 this->colourOpts.dumpToTextStream(out);
73 #include <pcl/io/pcd_io.h>
74 #include <pcl/point_types.h>
78 void CColouredPointsMap::reserve(
size_t newLength)
80 m_x.reserve(newLength);
81 m_y.reserve(newLength);
82 m_z.reserve(newLength);
83 m_color_R.reserve(newLength);
84 m_color_G.reserve(newLength);
85 m_color_B.reserve(newLength);
91 void CColouredPointsMap::resize(
size_t newLength)
93 m_x.resize(newLength, 0);
94 m_y.resize(newLength, 0);
95 m_z.resize(newLength, 0);
96 m_color_R.resize(newLength, 1);
97 m_color_G.resize(newLength, 1);
98 m_color_B.resize(newLength, 1);
107 m_x.assign(newLength, 0);
108 m_y.assign(newLength, 0);
109 m_z.assign(newLength, 0);
110 m_color_R.assign(newLength, 1);
111 m_color_G.assign(newLength, 1);
112 m_color_B.assign(newLength, 1);
121 CPointsMap::base_copyFrom(
135 uint8_t CColouredPointsMap::serializeGetVersion()
const {
return 9; }
149 out << m_color_R << m_color_G << m_color_B;
151 out << genericMapParams;
152 insertionOptions.writeToStream(
154 likelihoodOptions.writeToStream(out);
157 void CColouredPointsMap::serializeFrom(
175 in.ReadBufferFixEndianness(&m_x[0],
n);
176 in.ReadBufferFixEndianness(&m_y[0],
n);
177 in.ReadBufferFixEndianness(&m_z[0],
n);
179 in >> m_color_R >> m_color_G >> m_color_B;
182 in >> genericMapParams;
185 bool disableSaveAs3DObject;
186 in >> disableSaveAs3DObject;
187 genericMapParams.enableSaveAs3DObject = !disableSaveAs3DObject;
189 insertionOptions.readFromStream(
in);
190 likelihoodOptions.readFromStream(
in);
213 in.ReadBufferFixEndianness(&m_x[0],
n);
214 in.ReadBufferFixEndianness(&m_y[0],
n);
215 in.ReadBufferFixEndianness(&m_z[0],
n);
234 std::vector<uint32_t> dummy_pointWeight(
n);
235 in.ReadBufferFixEndianness(
236 &dummy_pointWeight[0],
n);
241 std::vector<uint32_t> dummy_pointWeight(
n);
242 in.ReadBufferFixEndianness(&dummy_pointWeight[0],
n);
250 in >> insertionOptions.minDistBetweenLaserPoints >>
251 insertionOptions.addToExistingPointsMap >>
252 insertionOptions.also_interpolate >>
253 insertionOptions.disableDeletion >>
254 insertionOptions.fuseWithExisting >>
255 insertionOptions.isPlanarMap;
259 bool old_matchStaticPointsOnly;
260 in >> old_matchStaticPointsOnly;
263 in >> insertionOptions.maxDistForInterpolatePoints;
265 bool disableSaveAs3DObject;
266 in >> disableSaveAs3DObject;
267 genericMapParams.enableSaveAs3DObject =
268 !disableSaveAs3DObject;
274 in >> insertionOptions.horizontalTolerance;
279 in >> m_color_R >> m_color_G >> m_color_B;
286 std::vector<float> dummy_dist;
292 m_color_R.assign(m_x.size(), 1.0f);
293 m_color_G.assign(m_x.size(), 1.0f);
294 m_color_B.assign(m_x.size(), 1.0f);
299 likelihoodOptions.readFromStream(
in);
302 in >> insertionOptions.insertInvalidPoints;
313 void CColouredPointsMap::internal_clear()
330 void CColouredPointsMap::setPoint(
331 size_t index,
float x,
float y,
float z,
float R,
float G,
float B)
337 this->m_color_R[
index] =
R;
338 this->m_color_G[
index] =
G;
339 this->m_color_B[
index] = B;
346 void CColouredPointsMap::setPointColor(
size_t index,
float R,
float G,
float B)
349 this->m_color_R[
index] =
R;
350 this->m_color_G[
index] =
G;
351 this->m_color_B[
index] = B;
355 void CColouredPointsMap::insertPointFast(
float x,
float y,
float z)
360 m_color_R.push_back(1);
361 m_color_G.push_back(1);
362 m_color_B.push_back(1);
367 void CColouredPointsMap::insertPoint(
368 float x,
float y,
float z,
float R,
float G,
float B)
373 m_color_R.push_back(
R);
374 m_color_G.push_back(
G);
375 m_color_B.push_back(B);
383 void CColouredPointsMap::getAs3DObject(
388 if (!genericMapParams.enableSaveAs3DObject)
return;
391 mrpt::make_aligned_shared<opengl::CPointCloudColoured>();
393 obj->loadFromPointsMap(
this);
394 obj->setColor(1, 1, 1, 1.0);
396 obj->setPointSize(this->renderOptions.point_size);
404 CColouredPointsMap::TColourOptions::TColourOptions()
405 : scheme(cmFromHeightRelativeToSensor), z_min(-10), z_max(10), d_max(5)
412 scheme =
source.read_enum(section,
"scheme", scheme);
419 std::ostream& out)
const
421 out <<
"\n----------- [CColouredPointsMap::TColourOptions] ------------ "
424 out <<
"scheme = " << scheme << endl;
425 out <<
"z_min = " << z_min << endl;
426 out <<
"z_max = " << z_max << endl;
427 out <<
"d_max = " << d_max << endl;
431 size_t index,
float&
x,
float&
y,
float&
z)
const
446 size_t index,
float&
x,
float&
y,
float&
z,
float&
R,
float&
G,
463 size_t index,
float&
R,
float&
G,
float& B)
const
477 bool accept_points_behind)
481 const double x = P.
x / P.
z;
482 const double y = P.
y / P.
z;
486 const double r4 =
square(r2);
487 const double r6 = r2 * r4;
514 cameraPoseW = robotPose + cameraPoseR;
521 std::vector<TPixelCoordf>
525 std::vector<size_t> p_idx;
526 std::vector<float> p_dist;
527 std::vector<unsigned int> p_proj;
531 cameraPoseW.
x(), cameraPoseW.
y(),
536 for (
size_t k = 0; k < p_idx.size(); k++)
538 float d = sqrt(p_dist[k]);
539 size_t idx = p_idx[k];
545 projectedPoints.push_back(px);
551 unsigned int chR, chG, chB;
565 unsigned int n_proj = 0;
566 const float factor = 1.0f / 255;
570 for (itProPoints = projectedPoints.begin(), k = 0;
571 itProPoints != projectedPoints.end(); ++itProPoints, ++k)
574 if (itProPoints->x >= 0 && itProPoints->x < imgW &&
575 itProPoints->y > 0 && itProPoints->y < imgH)
577 unsigned int ii = p_idx[p_proj[k]];
579 (
unsigned int)itProPoints->x, (
unsigned int)itProPoints->y);
603 if (!f)
return false;
605 for (
unsigned int i = 0; i <
m_x.size(); i++)
607 f,
"%f %f %f %d %d %d\n",
m_x[i],
m_y[i],
m_z[i],
637 idx, pt.
x, pt.
y, pt.
z, pt_color->
R, pt_color->
G, pt_color->
B);
666 const CPointsMap& anotherMap,
const size_t nPreviousPoints)
668 const size_t nOther = anotherMap.
size();
676 for (
size_t i = 0, j = nPreviousPoints; i < nOther; i++, j++)
688 const std::string& filename,
bool save_as_binary)
const
691 pcl::PointCloud<pcl::PointXYZRGB> cloud;
693 const size_t nThis = this->
size();
698 cloud.is_dense =
false;
699 cloud.points.resize(cloud.width * cloud.height);
701 const float f = 255.f;
708 for (
size_t i = 0; i < nThis; ++i)
710 cloud.points[i].x =
m_x[i];
711 cloud.points[i].y =
m_y[i];
712 cloud.points[i].z =
m_z[i];
718 cloud.points[i].rgb = aux_val.f;
721 return 0 == pcl::io::savePCDFile(filename, cloud, save_as_binary);
754 lric.
fVars.resize(4);
769 const float rel_z = gz - lric.
HM.get_unsafe(2, 3);
772 float& pR = lric.
fVars[0];
773 float& pG = lric.
fVars[1];
774 float& pB = lric.
fVars[2];
775 const float& Az_1_color = lric.
fVars[3];
818 float& pR = lric.
fVars[0];
819 float& pG = lric.
fVars[1];
820 float& pB = lric.
fVars[2];
845 lric.
fVars.resize(9);
846 float& cx = lric.
fVars[5];
847 float& cy = lric.
fVars[6];
848 float& fx = lric.
fVars[7];
849 float& fy = lric.
fVars[8];
856 lric.
uVars.resize(4);
857 unsigned int& imgW = lric.
uVars[0];
858 unsigned int& imgH = lric.
uVars[1];
859 unsigned int& img_idx_x = lric.
uVars[2];
860 unsigned int& img_idx_y = lric.
uVars[3];
866 lric.
bVars.resize(3);
874 lric.
fVars[4] = 1.0f / 255;
876 hasValidIntensityImage =
false;
887 hasValidIntensityImage =
true;
893 hasColorIntensityImg =
902 simple_3d_to_color_relation =
924 float& pR = lric.
fVars[0];
925 float& pG = lric.
fVars[1];
926 float& pB = lric.
fVars[2];
927 float& Az_1_color = lric.
fVars[3];
928 float& K_8u = lric.
fVars[4];
929 float& cx = lric.
fVars[5];
930 float& cy = lric.
fVars[6];
931 float& fx = lric.
fVars[7];
932 float& fy = lric.
fVars[8];
934 unsigned int& imgW = lric.
uVars[0];
935 unsigned int& imgH = lric.
uVars[1];
936 unsigned int& img_idx_x = lric.
uVars[2];
937 unsigned int& img_idx_y = lric.
uVars[3];
941 const uint8_t& simple_3d_to_color_relation = lric.
bVars[2];
944 const float rel_z = gz - lric.
HM.get_unsafe(2, 3);
973 bool hasValidColor =
false;
974 if (simple_3d_to_color_relation)
976 hasValidColor =
true;
990 img_idx_x = cx + fx * pt.
x / pt.
z;
991 img_idx_y = cy + fy * pt.
y / pt.
z;
993 hasValidColor = img_idx_x < imgW &&
1000 if (hasValidColor && hasColorIntensityImg)
1003 img_idx_x, img_idx_y, 0);
1008 else if (hasValidColor && hasValidIntensityImage)
1011 img_idx_x, img_idx_y, 0);
1012 pR = pG = pB =
c * K_8u;
1032 float& pR = lric.
fVars[0];
1033 float& pG = lric.
fVars[1];
1034 float& pB = lric.
fVars[2];
1051 unsigned int& imgW = lric.
uVars[0];
1052 unsigned int& img_idx_x = lric.
uVars[2];
1053 unsigned int& img_idx_y = lric.
uVars[3];
1056 const uint8_t& simple_3d_to_color_relation = lric.
bVars[2];
1060 if (simple_3d_to_color_relation && hasValidIntensityImage)
1062 if (++img_idx_x >= imgW)
Lightweight 3D point (float version).
A pair (x,y) of pixel coordinates (subpixel resolution).
std::vector< float > fVars
Extra variables to be used as desired by the derived class.
void aux_projectPoint_with_distortion(const mrpt::math::TPoint3D &P, const TCamera ¶ms, TPixelCoordf &pixel, bool accept_points_behind)
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form,...
bool save3D_and_colour_to_text_file(const std::string &file) const
Save to a text file.
size_t size() const
Returns the number of stored points in the map.
size_t getWidth() const override
Returns the width of the image in pixels.
virtual void PLY_import_set_vertex(const size_t idx, const mrpt::math::TPoint3Df &pt, const mrpt::img::TColorf *pt_color=nullptr) override
In a base class, will be called after PLY_import_set_vertex_count() once for each loaded point.
int void fclose(FILE *f)
An OS-independent version of fclose.
A map of 2D/3D points with individual colours (RGB).
GLdouble GLdouble GLdouble GLdouble q
TColourOptions colorScheme
The options employed when inserting laser scans in the map.
double fx() const
Get the value of the focal length x-value (in pixels).
mrpt::img::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
virtual void setPoint(size_t index, float x, float y, float z, float R, float G, float B) override
Changes a given point from map.
void vector_strong_clear(VECTOR_T &v)
Like calling a std::vector<>'s clear() method, but really forcing deallocating the memory.
static void internal_loadFromRangeScan2D_prepareOneRange(CColouredPointsMap &me, const float gx, const float gy, const float gz, mrpt::maps::CPointsMap::TLaserRange2DInsertContext &lric)
Helper method fot the generic implementation of CPointsMap::loadFromRangeScan(), to be called once pe...
mrpt::aligned_std_vector< float > m_color_R
The color data.
static void internal_loadFromRangeScan3D_postPushBack(CColouredPointsMap &me, mrpt::maps::CPointsMap::TLaserRange3DInsertContext &lric)
Helper method fot the generic implementation of CPointsMap::loadFromRangeScan(), to be called after e...
Helper struct used for internal_loadFromRangeScan3D_prepareOneRange()
static void internal_loadFromRangeScan3D_postOneRange(CColouredPointsMap &me, mrpt::maps::CPointsMap::TLaserRange3DInsertContext &lric)
Helper method fot the generic implementation of CPointsMap::loadFromRangeScan(), to be called once pe...
#define MAP_DEFINITION_REGISTER(_CLASSNAME_STRINGS, _CLASSNAME_WITH_NS)
Registers one map class into TMetricMapInitializer factory.
GLsizei GLsizei GLuint * obj
Helper struct used for internal_loadFromRangeScan2D_prepareOneRange()
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
mrpt::aligned_std_vector< float > m_color_G
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors.
double norm() const
Returns the euclidean norm of vector: .
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Virtual base for specifying the kind and parameters of one map (normally, to be inserted into mrpt::m...
mrpt::img::CImage image
The image captured by the camera, that is, the main piece of information of this observation.
#define THROW_EXCEPTION(msg)
#define ASSERT_(f)
Defines an assertion mechanism.
T square(const T x)
Inline function for the square of a number.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
std::shared_ptr< CPointCloudColoured > Ptr
bool isColor() const
Returns true if the image is RGB, false if it is grayscale.
static void templ_loadFromRangeScan(Derived &obj, const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose)
double cy() const
Get the value of the principal point y-coordinate (in pixels).
This namespace contains representation of robot actions and observations.
Virtual base class for "archives": classes abstracting I/O streams.
GLsizei GLsizei GLchar * source
void jet2rgb(const float color_index, float &r, float &g, float &b)
Computes the RGB color components (range [0,1]) for the corresponding color index in the range [0,...
double fy() const
Get the value of the focal length y-value (in pixels).
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
static void internal_loadFromRangeScan2D_init(CColouredPointsMap &me, mrpt::maps::CPointsMap::TLaserRange2DInsertContext &lric)
Helper method fot the generic implementation of CPointsMap::loadFromRangeScan(), to be called only on...
Declares a virtual base class for all metric maps storage classes.
virtual bool savePCDFile(const std::string &filename, bool save_as_binary) const override
Save the point cloud as a PCL PCD file, in either ASCII or binary format.
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
double cx() const
Get the value of the principal point x-coordinate (in pixels).
This class allows loading and storing values and vectors of different types from a configuration text...
double x() const
Common members of all points & poses classes.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
virtual void PLY_import_set_vertex_count(const size_t N) override
In a base class, reserve memory to prepare subsequent calls to PLY_import_set_vertex.
double x
X,Y,Z coordinates.
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
virtual void getPoint(size_t index, float &x, float &y, float &z, float &R, float &G, float &B) const override
Retrieves a point and its color (colors range is [0,1])
bool hasIntensityImage
true means the field intensityImage contains valid data
A RGB color - floats in the range [0,1].
std::vector< float > points3D_x
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera.
virtual void setSize(size_t newLength) override
Resizes all point buffers so they can hold the given number of points, erasing all previous contents ...
@ cmFromHeightRelativeToSensorGray
mrpt::aligned_std_vector< float > m_z
unsigned char * get_unsafe(unsigned int col, unsigned int row, unsigned int channel=0) const
Access to pixels without checking boundaries - Use normally the () operator better,...
Structure to hold the parameters of a pinhole camera model.
mrpt::aligned_std_vector< float > m_y
@ cmFromHeightRelativeToSensorJet
mrpt::maps::CColouredPointsMap::TColourOptions colourOpts
std::vector< float > fVars
Extra variables to be used as desired by the derived class.
std::shared_ptr< CSetOfObjects > Ptr
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
void PLY_export_get_vertex(const size_t idx, mrpt::math::TPoint3Df &pt, bool &pt_has_color, mrpt::img::TColorf &pt_color) const override
In a base class, will be called after PLY_export_get_vertex_count() once for each exported point.
EIGEN_STRONG_INLINE void setSize(size_t row, size_t col)
Changes the size of matrix, maintaining its previous content as possible and padding with zeros where...
void resetPointsMinDist(float defValue=2000.0f)
Reset the minimum-observed-distance buffer for all the points to a predefined value.
mrpt::maps::CPointsMap::TInsertionOptions insertionOpts
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
static void internal_loadFromRangeScan2D_postPushBack(CColouredPointsMap &me, mrpt::maps::CPointsMap::TLaserRange2DInsertContext &lric)
Helper method fot the generic implementation of CPointsMap::loadFromRangeScan(), to be called after e...
int fprintf(FILE *fil, const char *format,...) noexcept MRPT_printf_format_check(2
An OS-independent version of fprintf.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
mrpt::maps::CPointsMap::TLikelihoodOptions likelihoodOpts
mrpt::aligned_std_vector< float > m_color_B
std::vector< unsigned int > uVars
static void internal_loadFromRangeScan3D_init(CColouredPointsMap &me, mrpt::maps::CPointsMap::TLaserRange3DInsertContext &lric)
Helper method fot the generic implementation of CPointsMap::loadFromRangeScan(), to be called only on...
size_t getHeight() const override
Returns the height of the image in pixels.
virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose=nullptr) override
See CPointsMap::loadFromRangeScan()
virtual void addFrom_classSpecific(const CPointsMap &anotherMap, const size_t nPreviousPoints) override
Auxiliary method called from within addFrom() automatically, to finish the copying of class-specific ...
#define ASSERT_NOT_EQUAL_(__A, __B)
bool colourFromObservation(const mrpt::obs::CObservationImage &obs, const mrpt::poses::CPose3D &robotPose)
Colour a set of points from a CObservationImage and the global pose of the robot.
This base provides a set of functions for maths stuff.
mrpt::aligned_std_vector< float > m_x
The point coordinates.
FILE * fopen(const char *fileName, const char *mode) noexcept
An OS-independent version of fopen.
GLsizei const GLchar ** string
void inverseComposePoint(const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=nullptr) const
Computes the 3D point L such as .
std::vector< uint8_t > bVars
float scan_x
In internal_loadFromRangeScan3D_prepareOneRange, these are the local coordinates of the scan points b...
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
static void internal_loadFromRangeScan3D_prepareOneRange(CColouredPointsMap &me, const float gx, const float gy, const float gz, mrpt::maps::CPointsMap::TLaserRange3DInsertContext &lric)
Helper method fot the generic implementation of CPointsMap::loadFromRangeScan(), to be called once pe...
const char * getChannelsOrder() const
Returns a string of the form "BGR","RGB" or "GRAY" indicating the channels ordering.
void WriteBufferFixEndianness(const T *ptr, size_t ElementCount)
Writes a sequence of elemental datatypes, taking care of reordering their bytes from the running arch...
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ionNamePrefix) override
Load all params from a config file/source.
Declares a class derived from "CObservation" that encapsules an image from a camera,...
unsigned __int32 uint32_t
const mrpt::obs::CObservation3DRangeScan & rangeScan
This namespace provides a OS-independent interface to many useful functions: filenames manipulation,...
GLenum const GLfloat * params
void kdTreeNClosestPoint2DIdx(float x0, float y0, size_t knn, std::vector< size_t > &out_idx, std::vector< float > &out_dist_sqr) const
KD Tree-based search for the N closest point to some given 2D coordinates and returns their indexes.
mrpt::img::TCamera cameraParams
Intrinsic and distortion parameters of the camera.
void getPointColor(size_t index, float &R, float &G, float &B) const
Retrieves a point color (colors range is [0,1])
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |