MRPT  1.9.9
CBox.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "opengl-precomp.h" // Precompiled header
11 
12 #include <mrpt/math/geometry.h>
13 #include <mrpt/opengl/CBox.h>
15 
16 using namespace mrpt;
17 using namespace mrpt::opengl;
18 using namespace mrpt::math;
19 using namespace std;
20 
22 
24  const mrpt::math::TPoint3D& corner1, const mrpt::math::TPoint3D& corner2,
25  bool is_wireframe, float lineWidth)
26  : m_wireframe(is_wireframe),
27  m_draw_border(false),
28  m_solidborder_color(0, 0, 0)
29 {
31  setBoxCorners(corner1, corner2);
32 }
33 
34 void CBox::render(const RenderContext& rc) const
35 {
36  switch (rc.shader_id)
37  {
39  if (!m_wireframe) CRenderizableShaderTriangles::render(rc);
40  break;
42  if (m_draw_border || m_wireframe)
44  break;
45  };
46 }
48 {
51 }
52 
54 {
57  vbd.clear();
58 
59  const std::array<mrpt::math::TPoint3D, 2> corner = {m_corner_min,
60  m_corner_max};
61 
62  for (unsigned int i = 0; i < 2; i++)
63  {
64  vbd.emplace_back(corner[0].x, corner[0].y, corner[i].z);
65  vbd.emplace_back(corner[0].x, corner[1].y, corner[i].z);
66 
67  vbd.emplace_back(corner[0].x, corner[1].y, corner[i].z);
68  vbd.emplace_back(corner[1].x, corner[1].y, corner[i].z);
69 
70  vbd.emplace_back(corner[1].x, corner[1].y, corner[i].z);
71  vbd.emplace_back(corner[1].x, corner[0].y, corner[i].z);
72 
73  vbd.emplace_back(corner[1].x, corner[0].y, corner[i].z);
74  vbd.emplace_back(corner[0].x, corner[0].y, corner[i].z);
75 
76  vbd.emplace_back(corner[i].x, corner[0].y, corner[0].z);
77  vbd.emplace_back(corner[i].x, corner[0].y, corner[1].z);
78 
79  vbd.emplace_back(corner[i].x, corner[1].y, corner[0].z);
80  vbd.emplace_back(corner[i].x, corner[1].y, corner[1].z);
81  }
82 
83  cbd.assign(vbd.size(), m_solidborder_color);
84 }
86 {
88  tris.clear();
89 
90  const auto &c0 = m_corner_min, &c1 = m_corner_max;
91  using P3 = mrpt::math::TPoint3D;
92 
93  // Front face:
94  tris.emplace_back(
95  P3(c1.x, c0.y, c0.z), P3(c0.x, c0.y, c0.z), P3(c1.x, c0.y, c1.z));
96  tris.emplace_back(
97  P3(c0.x, c0.y, c0.z), P3(c0.x, c0.y, c1.z), P3(c1.x, c0.y, c1.z));
98 
99  // Back face:
100  tris.emplace_back(
101  P3(c1.x, c1.y, c0.z), P3(c0.x, c1.y, c0.z), P3(c1.x, c1.y, c1.z));
102  tris.emplace_back(
103  P3(c0.x, c1.y, c0.z), P3(c0.x, c1.y, c1.z), P3(c1.x, c1.y, c1.z));
104 
105  // Left face:
106  tris.emplace_back(
107  P3(c0.x, c0.y, c0.z), P3(c0.x, c1.y, c0.z), P3(c0.x, c1.y, c1.z));
108  tris.emplace_back(
109  P3(c0.x, c0.y, c1.z), P3(c0.x, c0.y, c0.z), P3(c0.x, c1.y, c1.z));
110 
111  // Right face:
112  tris.emplace_back(
113  P3(c1.x, c0.y, c0.z), P3(c1.x, c1.y, c0.z), P3(c1.x, c1.y, c1.z));
114  tris.emplace_back(
115  P3(c1.x, c0.y, c1.z), P3(c1.x, c0.y, c0.z), P3(c1.x, c1.y, c1.z));
116 
117  // Bottom face:
118  tris.emplace_back(
119  P3(c0.x, c0.y, c0.z), P3(c1.x, c0.y, c0.z), P3(c1.x, c1.y, c0.z));
120  tris.emplace_back(
121  P3(c0.x, c1.y, c0.z), P3(c0.x, c0.y, c0.z), P3(c1.x, c1.y, c0.z));
122  // Top face:
123 
124  tris.emplace_back(
125  P3(c0.x, c0.y, c1.z), P3(c1.x, c0.y, c1.z), P3(c1.x, c1.y, c1.z));
126  tris.emplace_back(
127  P3(c0.x, c1.y, c1.z), P3(c0.x, c0.y, c1.z), P3(c1.x, c1.y, c1.z));
128 
129  // All faces, all vertices, same color:
130  for (auto& t : tris) t.setColor(m_color);
131 }
132 
133 uint8_t CBox::serializeGetVersion() const { return 1; }
135 {
136  writeToStreamRender(out);
137  // version 0
138  out << m_corner_min.x << m_corner_min.y << m_corner_min.z << m_corner_max.x
139  << m_corner_max.y << m_corner_max.z << m_wireframe << m_lineWidth;
140  // Version 1:
141  out << m_draw_border << m_solidborder_color;
142 }
143 
145 {
146  switch (version)
147  {
148  case 0:
149  case 1:
150  readFromStreamRender(in);
151  in >> m_corner_min.x >> m_corner_min.y >> m_corner_min.z >>
152  m_corner_max.x >> m_corner_max.y >> m_corner_max.z >>
153  m_wireframe >> m_lineWidth;
154  // Version 1:
155  if (version >= 1)
156  in >> m_draw_border >> m_solidborder_color;
157  else
158  {
159  m_draw_border = false;
160  }
161 
162  break;
163  default:
165  };
167 }
168 
170  const mrpt::math::TPoint3D& corner1, const mrpt::math::TPoint3D& corner2)
171 {
173 
174  // Order the coordinates so we always have the min/max in their right
175  // position:
176  m_corner_min.x = std::min(corner1.x, corner2.x);
177  m_corner_min.y = std::min(corner1.y, corner2.y);
178  m_corner_min.z = std::min(corner1.z, corner2.z);
179 
180  m_corner_max.x = std::max(corner1.x, corner2.x);
181  m_corner_max.y = std::max(corner1.y, corner2.y);
182  m_corner_max.z = std::max(corner1.z, corner2.z);
183 }
184 
186  [[maybe_unused]] const mrpt::poses::CPose3D& o,
187  [[maybe_unused]] double& dist) const
188 {
189  THROW_EXCEPTION("TO DO");
190 }
191 
194 {
195  bb_min = m_corner_min;
196  bb_max = m_corner_max;
197 
198  // Convert to coordinates of my parent:
199  m_pose.composePoint(bb_min, bb_min);
200  m_pose.composePoint(bb_max, bb_max);
201 }
void setBoxCorners(const mrpt::math::TPoint3D &corner1, const mrpt::math::TPoint3D &corner2)
Set the position and size of the box, from two corners in 3D.
Definition: CBox.cpp:169
A solid or wireframe box in 3D, defined by 6 rectangular faces parallel to the planes X...
Definition: CBox.h:40
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
To be added to all CSerializable-classes implementation files.
void notifyChange() const
Call to enable calling renderUpdateBuffers() before the next render() rendering iteration.
void onUpdateBuffers_Wireframe() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
Definition: CBox.cpp:53
STL namespace.
Renderizable generic renderer for objects using the triangles shader.
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.
Context for calls to render()
std::vector< mrpt::math::TPoint3Df > m_vertex_buffer_data
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
Definition: exceptions.h:97
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.
Definition: CBox.cpp:47
bool traceRay(const mrpt::poses::CPose3D &o, double &dist) const override
Ray tracing.
Definition: CBox.cpp:185
This base provides a set of functions for maths stuff.
void onUpdateBuffers_Triangles() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
Definition: CBox.cpp:85
static constexpr shader_id_t WIREFRAME
void serializeFrom(mrpt::serialization::CArchive &in, uint8_t serial_version) override
Pure virtual method for reading (deserializing) from an abstract archive.
Definition: CBox.cpp:144
TPoint3D_< double > TPoint3D
Lightweight 3D point.
Definition: TPoint3D.h:268
void getBoundingBox(mrpt::math::TPoint3D &bb_min, mrpt::math::TPoint3D &bb_max) const override
Evaluates the bounding box of this object (including possible children) in the coordinate frame of th...
Definition: CBox.cpp:192
void serializeTo(mrpt::serialization::CArchive &out) const override
Pure virtual method for writing (serializing) to an abstract archive.
Definition: CBox.cpp:134
static constexpr shader_id_t TRIANGLES
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
Definition: CBox.cpp:34
T x
X,Y,Z coordinates.
Definition: TPoint3D.h:29
std::vector< mrpt::img::TColor > m_color_buffer_data
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Virtual base class for "archives": classes abstracting I/O streams.
Definition: CArchive.h:54
std::vector< mrpt::opengl::TTriangle > m_triangles
List of triangles.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
mrpt::vision::TStereoCalibResults out
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:13
const auto bb_max
const auto bb_min
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
uint8_t serializeGetVersion() const override
Must return the current versioning number of the object.
Definition: CBox.cpp:133
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020