Skip to content

Commit 836ce33

Browse files
committed
WIP: new mrpt-viz library
1 parent 2270811 commit 836ce33

File tree

106 files changed

+20635
-55
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

106 files changed

+20635
-55
lines changed

libs/opengl/include/mrpt/opengl/CRenderizableShaderTriangles.h

-17
Original file line numberDiff line numberDiff line change
@@ -50,17 +50,6 @@ class CRenderizableShaderTriangles : public virtual CRenderizable
5050
m_vao.destroy();
5151
}
5252

53-
bool isLightEnabled() const { return m_enableLight; }
54-
void enableLight(bool enable = true) { m_enableLight = enable; }
55-
56-
/** Control whether to render the FRONT, BACK, or BOTH (default) set of
57-
* faces. Refer to docs for glCullFace().
58-
* Example: If set to `cullFaces(TCullFace::BACK);`, back faces will not be
59-
* drawn ("culled")
60-
*/
61-
void cullFaces(const TCullFace& cf) { m_cullface = cf; }
62-
TCullFace cullFaces() const { return m_cullface; }
63-
6453
/** @name Raw access to triangle shader buffer data
6554
* @{ */
6655
const auto& shaderTrianglesBuffer() const { return m_triangles; }
@@ -75,15 +64,9 @@ class CRenderizableShaderTriangles : public virtual CRenderizable
7564
/** Returns the bounding box of m_triangles, or (0,0,0)-(0,0,0) if empty. */
7665
const mrpt::math::TBoundingBoxf trianglesBoundingBox() const;
7766

78-
void params_serialize(mrpt::serialization::CArchive& out) const;
79-
void params_deserialize(mrpt::serialization::CArchive& in);
80-
8167
private:
8268
mutable Buffer m_trianglesBuffer;
8369
mutable VertexArrayObject m_vao;
84-
85-
bool m_enableLight = true;
86-
TCullFace m_cullface = TCullFace::NONE;
8770
};
8871

8972
} // namespace mrpt::opengl

libs/opengl/include/mrpt/opengl/CRenderizableShaderWireFrame.h

-16
Original file line numberDiff line numberDiff line change
@@ -39,19 +39,6 @@ class CRenderizableShaderWireFrame : public virtual CRenderizable
3939
* to be drawn in "m_*_buffer" fields. */
4040
virtual void onUpdateBuffers_Wireframe() = 0;
4141

42-
void setLineWidth(float w)
43-
{
44-
m_lineWidth = w;
45-
CRenderizable::notifyChange();
46-
}
47-
float getLineWidth() const { return m_lineWidth; }
48-
void enableAntiAliasing(bool enable = true)
49-
{
50-
m_antiAliasing = enable;
51-
CRenderizable::notifyChange();
52-
}
53-
bool isAntiAliasingEnabled() const { return m_antiAliasing; }
54-
5542
// See base docs
5643
void freeOpenGLResources() override
5744
{
@@ -73,9 +60,6 @@ class CRenderizableShaderWireFrame : public virtual CRenderizable
7360
mutable std::vector<mrpt::img::TColor> m_color_buffer_data;
7461
mutable mrpt::containers::NonCopiableData<std::shared_mutex> m_wireframeMtx;
7562

76-
float m_lineWidth = 1.0f;
77-
bool m_antiAliasing = false;
78-
7963
/** Returns the bounding box of m_vertex_buffer_data, or (0,0,0)-(0,0,0) if
8064
* empty. */
8165
const mrpt::math::TBoundingBox wireframeVerticesBoundingBox() const;

libs/opengl/src/CRenderizableShaderTriangles.cpp

-20
Original file line numberDiff line numberDiff line change
@@ -185,23 +185,3 @@ const math::TBoundingBoxf CRenderizableShaderTriangles::trianglesBoundingBox() c
185185

186186
return bb;
187187
}
188-
189-
void CRenderizableShaderTriangles::params_serialize(mrpt::serialization::CArchive& out) const
190-
{
191-
out.WriteAs<uint8_t>(0); // serialization version
192-
out << m_enableLight << static_cast<uint8_t>(m_cullface);
193-
}
194-
void CRenderizableShaderTriangles::params_deserialize(mrpt::serialization::CArchive& in)
195-
{
196-
const auto version = in.ReadAs<uint8_t>();
197-
198-
switch (version)
199-
{
200-
case 0:
201-
in >> m_enableLight;
202-
m_cullface = static_cast<TCullFace>(in.ReadAs<uint8_t>());
203-
break;
204-
default:
205-
MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
206-
};
207-
}

libs/viz/CMakeLists.txt

+19
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
# Lists of directories with source files:
2+
# See "DeclareMRPTLib.cmake" for explanations
3+
# -------------------------------------------------
4+
5+
#---------------------------------------------
6+
# Macro declared in "DeclareMRPTLib.cmake":
7+
#---------------------------------------------
8+
define_mrpt_lib(
9+
# Lib name
10+
viz
11+
# Dependencies:
12+
mrpt-poses
13+
mrpt-img
14+
)
15+
16+
if(NOT BUILD_mrpt-viz)
17+
return()
18+
endif()
19+

libs/viz/include/mrpt/viz/CArrow.h

+127
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,127 @@
1+
/* +------------------------------------------------------------------------+
2+
| Mobile Robot Programming Toolkit (MRPT) |
3+
| https://www.mrpt.org/ |
4+
| |
5+
| Copyright (c) 2005-2024, 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 <mrpt/viz/CVisualObject.h>
12+
13+
namespace mrpt::viz
14+
{
15+
/** A 3D arrow
16+
*
17+
* ![mrpt::viz::CArrow](preview_CArrow.png)
18+
*
19+
* \sa opengl::Scene
20+
* \ingroup mrpt_viz_grp
21+
*/
22+
class CArrow : virtual public CVisualObject, public VisualObjectParams_Triangles
23+
{
24+
DEFINE_SERIALIZABLE(CArrow, mrpt::viz)
25+
DEFINE_SCHEMA_SERIALIZABLE()
26+
27+
public:
28+
void setArrowEnds(float x0, float y0, float z0, float x1, float y1, float z1)
29+
{
30+
m_x0 = x0;
31+
m_y0 = y0;
32+
m_z0 = z0;
33+
m_x1 = x1;
34+
m_y1 = y1;
35+
m_z1 = z1;
36+
CVisualObject::notifyChange();
37+
}
38+
template <typename Vector3Like>
39+
void setArrowEnds(const Vector3Like& start, const Vector3Like& end)
40+
{
41+
m_x0 = start[0];
42+
m_y0 = start[1];
43+
m_z0 = start[2];
44+
m_x1 = end[0];
45+
m_y1 = end[1];
46+
m_z1 = end[2];
47+
CVisualObject::notifyChange();
48+
}
49+
void setHeadRatio(float rat)
50+
{
51+
m_headRatio = rat;
52+
CVisualObject::notifyChange();
53+
}
54+
void setSmallRadius(float rat)
55+
{
56+
m_smallRadius = rat;
57+
CVisualObject::notifyChange();
58+
}
59+
void setLargeRadius(float rat)
60+
{
61+
m_largeRadius = rat;
62+
CVisualObject::notifyChange();
63+
}
64+
/** Number of radial divisions */
65+
void setSlicesCount(uint32_t slices)
66+
{
67+
m_slices = slices;
68+
CVisualObject::notifyChange();
69+
}
70+
71+
/** Number of radial divisions */
72+
uint32_t getSlicesCount() const { return m_slices; }
73+
74+
mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const override;
75+
76+
/** Constructor */
77+
CArrow(
78+
float x0 = 0,
79+
float y0 = 0,
80+
float z0 = 0,
81+
float x1 = 1,
82+
float y1 = 1,
83+
float z1 = 1,
84+
float headRatio = 0.2f,
85+
float smallRadius = 0.05f,
86+
float largeRadius = 0.2f) :
87+
m_x0(x0),
88+
m_y0(y0),
89+
m_z0(z0),
90+
m_x1(x1),
91+
m_y1(y1),
92+
m_z1(z1),
93+
m_headRatio(headRatio),
94+
m_smallRadius(smallRadius),
95+
m_largeRadius(largeRadius)
96+
{
97+
}
98+
99+
CArrow(
100+
const mrpt::math::TPoint3Df& from,
101+
const mrpt::math::TPoint3Df& to,
102+
float headRatio = 0.2f,
103+
float smallRadius = 0.05f,
104+
float largeRadius = 0.2f) :
105+
m_x0(from.x),
106+
m_y0(from.y),
107+
m_z0(from.z),
108+
m_x1(to.x),
109+
m_y1(to.y),
110+
m_z1(to.z),
111+
m_headRatio(headRatio),
112+
m_smallRadius(smallRadius),
113+
m_largeRadius(largeRadius)
114+
{
115+
}
116+
~CArrow() override = default;
117+
118+
protected:
119+
mutable float m_x0, m_y0, m_z0;
120+
mutable float m_x1, m_y1, m_z1;
121+
float m_headRatio;
122+
float m_smallRadius, m_largeRadius;
123+
/** Number of radial divisions. */
124+
uint32_t m_slices = 10;
125+
};
126+
127+
} // namespace mrpt::viz
+106
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,106 @@
1+
/* +------------------------------------------------------------------------+
2+
| Mobile Robot Programming Toolkit (MRPT) |
3+
| https://www.mrpt.org/ |
4+
| |
5+
| Copyright (c) 2005-2024, 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 <mrpt/img/CImage.h>
12+
#include <mrpt/viz/CVisualObject.h>
13+
14+
#include <map>
15+
#include <optional>
16+
17+
namespace mrpt::viz
18+
{
19+
/** This class can load & render 3D models in a number of different formats
20+
* (requires the library assimp).
21+
* - All supported formats:
22+
* http://assimp.sourceforge.net/main_features_formats.html
23+
* - Most common ones: AutoCAD DXF ( .dxf ), Collada ( .dae ), Blender 3D (
24+
* .blend ), 3ds Max 3DS ( .3ds ), 3ds Max ASE ( .ase ), Quake I ( .mdl ), Quake
25+
* II ( .md2 ), Quake III Mesh ( .md3 ), etc.
26+
*
27+
* Models are loaded via CAssimpModel::loadScene()
28+
*
29+
* ![mrpt::viz::CAssimpModel](preview_CAssimpModel.png)
30+
*
31+
* \sa opengl::Scene
32+
* \ingroup mrpt_viz_grp
33+
*/
34+
class CAssimpModel : public CVisualObject
35+
{
36+
DEFINE_SERIALIZABLE(CAssimpModel, mrpt::viz)
37+
38+
public:
39+
CAssimpModel();
40+
virtual ~CAssimpModel() override;
41+
42+
/** Import flags for loadScene
43+
* \note Not defined as ``enum class`` to allow C++-valid or-wise combinations
44+
*/
45+
struct LoadFlags
46+
{
47+
enum flags_t : uint32_t
48+
{
49+
/** See: aiProcessPreset_TargetRealtime_Fast */
50+
RealTimeFast = 0x0001,
51+
52+
/** See: aiProcessPreset_TargetRealtime_Quality */
53+
RealTimeQuality = 0x0002,
54+
55+
/** See: aiProcessPreset_TargetRealtime_MaxQuality */
56+
RealTimeMaxQuality = 0x0004,
57+
58+
/** See: aiProcess_FlipUVs */
59+
FlipUVs = 0x0010,
60+
61+
/** MRPT-specific: ignore materials and replace by the base class
62+
CRenderizable uniform color that was defined before calling
63+
loadScene(). \note (New in MRPT 2.5.0) */
64+
IgnoreMaterialColor = 0x0100,
65+
66+
/** Displays messages on loaded textures, etc. */
67+
Verbose = 0x1000
68+
};
69+
};
70+
71+
using filepath_t = std::string;
72+
73+
/** Loads a scene from a file in any supported file.
74+
* \exception std::runtime_error On any error during loading or importing
75+
* the file.
76+
*/
77+
void loadScene(
78+
const std::string& file_name,
79+
const int flags = LoadFlags::RealTimeMaxQuality | LoadFlags::FlipUVs | LoadFlags::Verbose);
80+
81+
/** Empty the object */
82+
void clear();
83+
84+
/* Simulation of ray-trace. */
85+
bool traceRay(const mrpt::poses::CPose3D& o, double& dist) const override;
86+
87+
mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const override;
88+
89+
/** Enable (or disable if set to .0f) a feature in which textured triangles
90+
* are split into different renderizable smaller objects.
91+
* This is required only for semitransparent objects with overlaping regions.
92+
*/
93+
void split_triangles_rendering_bbox(const float bbox_size);
94+
95+
[[nodiscard]] float split_triangles_rendering_bbox() const
96+
{
97+
return m_split_triangles_rendering_bbox;
98+
}
99+
100+
private:
101+
filepath_t m_modelPath;
102+
uint32_t m_modelLoadFlags = 0;
103+
float m_split_triangles_rendering_bbox = .0f;
104+
};
105+
106+
} // namespace mrpt::viz

0 commit comments

Comments
 (0)