VerticalPlane.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2024 Jose Luis Blanco Claraco |
5  | Copyright (C) 2017 Borys Tymchenko (Odessa Polytechnic University) |
6  | Distributed under 3-clause BSD License |
7  | See COPYING |
8  +-------------------------------------------------------------------------+ */
9 
10 #include <mrpt/opengl/COpenGLScene.h>
11 #include <mrpt/system/filesystem.h>
12 #include <mrpt/version.h>
13 #include <mvsim/World.h>
15 
16 #include <rapidxml.hpp>
17 
18 #include "JointXMLnode.h"
19 #include "xml_utils.h"
20 
21 using namespace rapidxml;
22 using namespace mvsim;
23 using namespace std;
24 
25 VerticalPlane::VerticalPlane(World* parent, const rapidxml::xml_node<char>* root)
26  : WorldElementBase(parent)
27 {
28  // Create opengl object: in this class, we'll store most state data directly
29  // in the mrpt::opengl object.
31 }
32 
34 
36 {
37  ASSERT_(root);
38 
39  // Common setup for simulable objects:
40  // -----------------------------------------------------------
41  {
43  p.init_pose_mandatory = false;
44 
45  JointXMLnode<> jnode;
46  jnode.add(root);
47  parseSimulable(jnode, p);
48  }
49 
50  TParameterDefinitions params;
51  params["color"] = TParamEntry("%color", &color_);
52  params["enable_shadows"] = TParamEntry("%bool", &enableShadows_);
53 
54  params["x0"] = TParamEntry("%f", &x0_);
55  params["x1"] = TParamEntry("%f", &x1_);
56  params["y0"] = TParamEntry("%f", &y0_);
57  params["y1"] = TParamEntry("%f", &y1_);
58  params["z"] = TParamEntry("%f", &z_);
59  params["height"] = TParamEntry("%f", &height_);
60  params["cull_face"] = TParamEntry("%s", &cull_faces_);
61 
62  params["texture"] = TParamEntry("%s", &textureFileName_);
63  params["texture_size_x"] = TParamEntry("%lf", &textureSizeX_);
64  params["texture_size_y"] = TParamEntry("%lf", &textureSizeY_);
65 
67 
68  // Create box2d fixtures, to enable collision detection:
69  // --------------------------------------------------------
70  b2World& world = *world_->getBox2DWorld();
71 
72  // Define the dynamic body. We set its position and call the body factory.
73  b2BodyDef bodyDef;
74  bodyDef.type = b2_staticBody;
75 
76  b2dBody_ = world.CreateBody(&bodyDef);
77 
78  // Define shape of block:
79  // ------------------------------
80  {
81  const float thickness = 0.02f;
82 
83  const mrpt::math::TPoint2Df p0 = {x0_, y0_};
84  const mrpt::math::TPoint2Df p1 = {x1_, y1_};
85  ASSERT_(p0 != p1);
86  const auto v01 = p1 - p0;
87  const mrpt::math::TPoint2Df normal = {-v01.y, v01.x};
88  const auto w = normal.unitarize() * thickness;
89 
90  // Convert shape into Box2D format:
91  const size_t nPts = 4;
92  std::vector<b2Vec2> pts;
93 
94  const auto p00 = p0 - w, p01 = p0 + w;
95  const auto p10 = p1 - w, p11 = p1 + w;
96 
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);
101 
102  b2PolygonShape blockPoly;
103  blockPoly.Set(&pts[0], nPts);
104 
105  // Define the dynamic body fixture.
106  b2FixtureDef fixtureDef;
107  fixtureDef.shape = &blockPoly;
108  fixtureDef.restitution = restitution_;
109 
110  // Add the shape to the body.
111  fixture_block_ = b2dBody_->CreateFixture(&fixtureDef);
112  }
113 
114  // Init pos: (the vertices already have the global coordinates)
115  b2dBody_->SetTransform(b2Vec2(0, 0), 0);
116 }
117 
119  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
120  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& physical,
121  [[maybe_unused]] bool childrenOnly)
122 {
123  using namespace mrpt::math;
124  using namespace std::string_literals;
125 
126  if (!glGroup_) glGroup_ = mrpt::opengl::CSetOfObjects::Create();
127 
128  // 1st call? (w/o texture)
129  if (!gl_plane_ && textureFileName_.empty() && viz && physical)
130  {
131  const mrpt::math::TPoint3Df p0 = {x0_, y0_, z_};
132  const mrpt::math::TPoint3Df p1 = {x1_, y1_, z_};
133 
134  ASSERT_(p0 != p1);
135  const auto v01 = p1 - p0;
136 
137  const float L = v01.norm(), H = height_;
138 
139  const auto center = (p0 + p1) * 0.5f + mrpt::math::TPoint3Df(0, 0, 0.5f * H);
140 
141  gl_plane_ = mrpt::opengl::CTexturedPlane::Create();
142  gl_plane_->setPlaneCorners(-0.5 * L, 0.5 * L, -0.5 * H, 0.5 * H);
143 
144  mrpt::math::TPose3D p;
145  p.x = center.x;
146  p.y = center.y;
147  p.z = center.z;
148  p.yaw = std::atan2(v01.y, v01.x);
149  p.roll = mrpt::DEG2RAD(90.0);
150 
151  const auto pp = parent()->applyWorldRenderOffset(p);
152 
153  gl_plane_->setPose(pp);
154  gl_plane_->setName("VerticalPlane_"s + getName());
155 
156 #if MRPT_VERSION >= 0x270
157  gl_plane_->enableLighting(enableShadows_);
158 #endif
159 
160  gl_plane_->setColor_u8(color_);
161 
162 #if MRPT_VERSION >= 0x240
163  gl_plane_->cullFaces(
164  mrpt::typemeta::TEnumType<mrpt::opengl::TCullFace>::name2value(cull_faces_));
165 #endif
166  glGroup_->insert(gl_plane_);
167  viz->get().insert(glGroup_);
168  physical->get().insert(glGroup_);
169  }
170  // 1st call? (with texture)
171  if (!gl_plane_text_ && !textureFileName_.empty() && viz && physical)
172  {
173  const std::string localFileName = world_->xmlPathToActualPath(textureFileName_);
174  ASSERT_FILE_EXISTS_(localFileName);
175 
176  mrpt::img::CImage texture;
177  bool textureReadOk = texture.loadFromFile(localFileName);
178  ASSERT_(textureReadOk);
179 
180  const mrpt::math::TPoint3Df p0 = {x0_, y0_, z_};
181  const mrpt::math::TPoint3Df p1 = {x1_, y1_, z_};
182 
183  ASSERT_(p0 != p1);
184  const auto v01 = p1 - p0;
185 
186  const float L = v01.norm(), H = height_;
187 
188  // Compute (U,V) texture coordinates:
189  float u_min = 0;
190  float v_min = 0;
191  float u_max = L / textureSizeX_;
192  float v_max = H / textureSizeY_;
193 
194  gl_plane_text_ = mrpt::opengl::CSetOfTexturedTriangles::Create();
195  gl_plane_text_->setName("VerticalPlane_"s + getName());
196 
197  gl_plane_text_->enableLight(enableShadows_);
198 
199  {
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};
204 
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};
208 
209  t.computeNormals();
210  gl_plane_text_->insertTriangle(t);
211  }
212  {
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};
217 
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};
221 
222  t.computeNormals();
223  gl_plane_text_->insertTriangle(t);
224  }
225 
226  gl_plane_text_->assignImage(texture);
227 
228 #if MRPT_VERSION >= 0x240
229  gl_plane_text_->cullFaces(
230  mrpt::typemeta::TEnumType<mrpt::opengl::TCullFace>::name2value(cull_faces_));
231 #endif
232 
233  glGroup_->insert(gl_plane_text_);
234  viz->get().insert(glGroup_);
235  physical->get().insert(glGroup_);
236  }
237 
238  // Update them:
239  // If "viz" does not have a value, it's because we are already inside a
240  // setPose() change event, so my caller already holds the mutex and we
241  // don't need/can't acquire it again:
242  const auto objectPose = viz.has_value() ? getPose() : getPoseNoLock();
243  glGroup_->setPose(objectPose);
244 }
245 
247 {
249 }
250 
252 {
254 }
mvsim::VisualObject::parent
World * parent()
Definition: VisualObject.h:51
mvsim
Definition: Client.h:21
mvsim::Simulable::getName
const std::string & getName() const
Definition: Simulable.h:107
mvsim::VisualObject::world_
World * world_
Definition: VisualObject.h:73
mvsim::VerticalPlane::gl_plane_
mrpt::opengl::CTexturedPlane::Ptr gl_plane_
Definition: VerticalPlane.h:53
mvsim::VerticalPlane::x1_
float x1_
Definition: VerticalPlane.h:41
mvsim::JointXMLnode
Definition: basic_types.h:53
b2Body::SetTransform
void SetTransform(const b2Vec2 &position, float angle)
Definition: b2_body.cpp:415
mvsim::ParseSimulableParams::init_pose_mandatory
bool init_pose_mandatory
Definition: Simulable.h:32
mvsim::TParamEntry
Definition: TParameterDefinitions.h:38
JointXMLnode.h
s
XmlRpcServer s
mvsim::parse_xmlnode_children_as_param
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const TParameterDefinitions &params, const std::map< std::string, std::string > &variableNamesValues={}, const char *functionNameContext="", mrpt::system::COutputLogger *logger=nullptr)
Definition: xml_utils.cpp:215
mvsim::VerticalPlane::cull_faces_
std::string cull_faces_
Definition: VerticalPlane.h:51
mvsim::World::applyWorldRenderOffset
mrpt::math::TPose3D applyWorldRenderOffset(mrpt::math::TPose3D p) const
Definition: World.h:631
World.h
b2_staticBody
@ b2_staticBody
Definition: b2_body.h:45
mvsim::VerticalPlane::x0_
float x0_
Definition: VerticalPlane.h:41
b2FixtureDef
Definition: b2_fixture.h:61
mvsim::VerticalPlane::textureFileName_
std::string textureFileName_
Definition: VerticalPlane.h:46
mvsim::VerticalPlane::b2dBody_
b2Body * b2dBody_
Definition: VerticalPlane.h:57
b2Vec2
A 2D column vector.
Definition: b2_math.h:41
xml_utils.h
b2PolygonShape::Set
void Set(const b2Vec2 *points, int32 count)
Definition: b2_polygon_shape.cpp:118
f
f
b2BodyDef::type
b2BodyType type
Definition: b2_body.h:74
mvsim::VerticalPlane::color_
mrpt::img::TColor color_
Definition: VerticalPlane.h:42
mvsim::VerticalPlane::z_
float z_
Definition: VerticalPlane.h:50
mvsim::VerticalPlane::height_
float height_
Definition: VerticalPlane.h:50
b2FixtureDef::restitution
float restitution
The restitution (elasticity) usually in the range [0,1].
Definition: b2_fixture.h:85
mvsim::VerticalPlane::simul_pre_timestep
void simul_pre_timestep(const TSimulContext &context) override
Definition: VerticalPlane.cpp:246
rapidxml
Definition: rapidxml.hpp:57
mvsim::TSimulContext
Definition: basic_types.h:58
mvsim::World::xmlPathToActualPath
std::string xmlPathToActualPath(const std::string &modelURI) const
Definition: World.cpp:98
mvsim::TParameterDefinitions
std::map< std::string, TParamEntry > TParameterDefinitions
Definition: TParameterDefinitions.h:64
mvsim::VerticalPlane::textureSizeX_
double textureSizeX_
Definition: VerticalPlane.h:47
mvsim::VerticalPlane::~VerticalPlane
virtual ~VerticalPlane()
Definition: VerticalPlane.cpp:33
mvsim::Simulable::simul_post_timestep
virtual void simul_post_timestep(const TSimulContext &context)
Definition: Simulable.cpp:64
mvsim::VerticalPlane::textureSizeY_
double textureSizeY_
Definition: VerticalPlane.h:48
mvsim::World::getBox2DWorld
std::unique_ptr< b2World > & getBox2DWorld()
Definition: World.h:307
mvsim::VerticalPlane::simul_post_timestep
void simul_post_timestep(const TSimulContext &context) override
Definition: VerticalPlane.cpp:251
b2BodyDef
Definition: b2_body.h:52
b2FixtureDef::shape
const b2Shape * shape
Definition: b2_fixture.h:76
mvsim::World
Definition: World.h:82
mvsim::VerticalPlane::y1_
float y1_
Definition: VerticalPlane.h:41
rapidxml::xml_node< char >
b2World::CreateBody
b2Body * CreateBody(const b2BodyDef *def)
Definition: b2_world.cpp:115
mvsim::World::user_defined_variables
const std::map< std::string, std::string > & user_defined_variables() const
Definition: World.h:390
b2PolygonShape
Definition: b2_polygon_shape.h:32
mvsim::ParseSimulableParams
Definition: Simulable.h:28
mvsim::VerticalPlane::glGroup_
mrpt::opengl::CSetOfObjects::Ptr glGroup_
Definition: VerticalPlane.h:55
std
mvsim::VerticalPlane::enableShadows_
bool enableShadows_
Definition: VerticalPlane.h:43
mvsim::Simulable::simul_pre_timestep
virtual void simul_pre_timestep(const TSimulContext &context)
Definition: Simulable.cpp:35
mvsim::VerticalPlane::gl_plane_text_
mrpt::opengl::CSetOfTexturedTriangles::Ptr gl_plane_text_
Definition: VerticalPlane.h:54
mrpt::math
Definition: xml_utils.h:22
mvsim::VerticalPlane::y0_
float y0_
Definition: VerticalPlane.h:41
b2World
Definition: b2_world.h:46
mvsim::Simulable::getPose
mrpt::math::TPose3D getPose() const
Definition: Simulable.cpp:490
root
root
mvsim::VerticalPlane::internalGuiUpdate
virtual void internalGuiUpdate(const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
Definition: VerticalPlane.cpp:118
VerticalPlane.h
rapidxml.hpp
mvsim::WorldElementBase
Definition: WorldElementBase.h:27
t
geometry_msgs::TransformStamped t
mvsim::VerticalPlane::loadConfigFrom
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
Definition: VerticalPlane.cpp:35
mvsim::Simulable::getPoseNoLock
mrpt::math::TPose3D getPoseNoLock() const
No thread-safe version. Used internally only.
Definition: Simulable.cpp:496
mvsim::VerticalPlane::restitution_
double restitution_
Default: 0.01.
Definition: VerticalPlane.h:58
mvsim::VerticalPlane::fixture_block_
b2Fixture * fixture_block_
Definition: VerticalPlane.h:59
b2Body::CreateFixture
b2Fixture * CreateFixture(const b2FixtureDef *def)
Definition: b2_body.cpp:165
mvsim::JointXMLnode::add
void add(const rapidxml::xml_node< Ch > *node)
Definition: JointXMLnode.h:28


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:08