10 #include <mrpt/opengl/COpenGLScene.h>
11 #include <mrpt/system/filesystem.h>
12 #include <mrpt/version.h>
22 using namespace mvsim;
47 parseSimulable(jnode, p);
81 const float thickness = 0.02f;
83 const mrpt::math::TPoint2Df p0 = {
x0_,
y0_};
84 const mrpt::math::TPoint2Df p1 = {
x1_,
y1_};
86 const auto v01 = p1 - p0;
87 const mrpt::math::TPoint2Df normal = {-v01.y, v01.x};
88 const auto w = normal.unitarize() * thickness;
91 const size_t nPts = 4;
92 std::vector<b2Vec2> pts;
94 const auto p00 = p0 - w, p01 = p0 + w;
95 const auto p10 = p1 - w, p11 = p1 + w;
97 pts.emplace_back(p00.x, p00.y);
98 pts.emplace_back(p01.x, p01.y);
99 pts.emplace_back(p11.x, p11.y);
100 pts.emplace_back(p10.x, p10.y);
103 blockPoly.
Set(&pts[0], nPts);
107 fixtureDef.
shape = &blockPoly;
119 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
120 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& physical,
121 [[maybe_unused]]
bool childrenOnly)
124 using namespace std::string_literals;
131 const mrpt::math::TPoint3Df p0 = {
x0_,
y0_,
z_};
132 const mrpt::math::TPoint3Df p1 = {
x1_,
y1_,
z_};
135 const auto v01 = p1 - p0;
137 const float L = v01.norm(), H =
height_;
139 const auto center = (p0 + p1) * 0.5
f + mrpt::math::TPoint3Df(0, 0, 0.5
f * H);
141 gl_plane_ = mrpt::opengl::CTexturedPlane::Create();
142 gl_plane_->setPlaneCorners(-0.5 * L, 0.5 * L, -0.5 * H, 0.5 * H);
144 mrpt::math::TPose3D p;
148 p.yaw = std::atan2(v01.y, v01.x);
149 p.roll = mrpt::DEG2RAD(90.0);
156 #if MRPT_VERSION >= 0x270
162 #if MRPT_VERSION >= 0x240
164 mrpt::typemeta::TEnumType<mrpt::opengl::TCullFace>::name2value(
cull_faces_));
174 ASSERT_FILE_EXISTS_(localFileName);
176 mrpt::img::CImage texture;
177 bool textureReadOk = texture.loadFromFile(localFileName);
178 ASSERT_(textureReadOk);
180 const mrpt::math::TPoint3Df p0 = {
x0_,
y0_,
z_};
181 const mrpt::math::TPoint3Df p1 = {
x1_,
y1_,
z_};
184 const auto v01 = p1 - p0;
186 const float L = v01.norm(), H =
height_;
200 mrpt::opengl::CSetOfTexturedTriangles::TTriangle
t;
201 t.vertices[0].xyzrgba.pt = {
x0_,
y0_,
z_};
202 t.vertices[1].xyzrgba.pt = {
x1_,
y1_,
z_};
203 t.vertices[2].xyzrgba.pt = {
x1_,
y1_,
z_ + H};
205 t.vertices[0].uv = {u_min, v_min};
206 t.vertices[1].uv = {u_max, v_min};
207 t.vertices[2].uv = {u_max, v_max};
213 mrpt::opengl::CSetOfTexturedTriangles::TTriangle
t;
214 t.vertices[0].xyzrgba.pt = {
x0_,
y0_,
z_};
215 t.vertices[1].xyzrgba.pt = {
x1_,
y1_,
z_ + H};
216 t.vertices[2].xyzrgba.pt = {
x0_,
y0_,
z_ + H};
218 t.vertices[0].uv = {u_min, v_min};
219 t.vertices[1].uv = {u_max, v_max};
220 t.vertices[2].uv = {u_min, v_max};
228 #if MRPT_VERSION >= 0x240
230 mrpt::typemeta::TEnumType<mrpt::opengl::TCullFace>::name2value(
cull_faces_));