World_walls.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2023 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/core/exceptions.h>
11 #include <mrpt/maps/CSimplePointsMap.h>
12 #include <mrpt/opengl/CAssimpModel.h>
13 #include <mrpt/system/filesystem.h>
14 #include <mvsim/World.h>
15 
16 #include <rapidxml.hpp>
17 #include <rapidxml_print.hpp>
18 #include <rapidxml_utils.hpp>
19 
20 #include "xml_utils.h"
21 
22 using namespace mvsim;
23 using namespace std;
24 
26 {
27  double height = 2.0;
28  double thickness = 0.10;
29 };
30 
32  World* parent, const mrpt::math::TPoint3D& rawEnd1,
33  const mrpt::math::TPoint3D& rawEnd2, const WallProperties& wp,
34  mrpt::maps::CSimplePointsMap& allPts)
35 {
36  Block::Ptr b = std::make_shared<Block>(parent);
37 
38  {
39  static int cnt = 0;
40  b->setName(mrpt::format("wall_%04i", ++cnt));
41  }
42 
43  float pt1Dist = std::numeric_limits<float>::max(),
44  pt2Dist = std::numeric_limits<float>::max();
45 
46  if (!allPts.empty())
47  {
48  allPts.kdTreeClosestPoint2D(rawEnd1.x, rawEnd1.y, pt1Dist);
49  allPts.kdTreeClosestPoint2D(rawEnd2.x, rawEnd2.y, pt2Dist);
50  }
51 
52  // Do we need to move these points due to former points already there, to
53  // avoid "collisions"?
54  const bool end1move = pt1Dist < mrpt::square(1.01 * wp.thickness);
55  const bool end2move = pt2Dist < mrpt::square(1.01 * wp.thickness);
56 
57  const auto vec12 = rawEnd2 - rawEnd1;
58  ASSERT_(vec12.norm() > 0);
59  const auto u12 = vec12.unitarize();
60 
61  const double t_hf = 0.5 * wp.thickness;
62  const double t = 0.5 * wp.thickness;
63 
64  const auto end1 = end1move ? (rawEnd1 + u12 * (-t)) : rawEnd1;
65  const auto end2 = end2move ? (rawEnd2 + u12 * t) : rawEnd2;
66 
67  const auto ptCenter = (end1 + end2) * 0.5;
68  const double wallLineAngle = std::atan2(vec12.y, vec12.x);
69 
70  allPts.insertPoint(rawEnd1);
71  allPts.insertPoint(rawEnd2);
72 
73  // initial pose:
74  b->setPose({ptCenter.x, ptCenter.y, 0, wallLineAngle, 0, 0});
75 
76  // Shape:
77  {
78  const double l_hf = 0.5 * (end2 - end1).norm();
79 
80  ASSERT_(l_hf > 0);
81  ASSERT_(t_hf > 0);
82 
83  auto bbmin = mrpt::math::TPoint3D(-l_hf, -t_hf, 0);
84  auto bbmax = mrpt::math::TPoint3D(+l_hf, +t_hf, 0);
85 
86  mrpt::math::TPolygon2D p;
87  p.emplace_back(bbmin.x, bbmin.y);
88  p.emplace_back(bbmin.x, bbmax.y);
89  p.emplace_back(bbmax.x, bbmax.y);
90  p.emplace_back(bbmax.x, bbmin.y);
91 
92  b->blockShape(p);
93 
94  b->block_z_min(.0);
95  b->block_z_max(wp.height);
96  }
97 
98  // make the walls non-movable:
99  b->ground_friction(1e5);
100  b->mass(1e5);
101 
102  // Register bodies, fixtures, etc. in Box2D simulator:
103  // ----------------------------------------------------
104  b->create_multibody_system(*parent->getBox2DWorld());
105  // This makes the walls non-mobile:
106  b->setIsStatic(true);
107 
108  if (auto bb = b->b2d_body(); bb != nullptr)
109  {
110  // Init pos:
111  const auto q = b->getPose();
112 
113  bb->SetTransform(b2Vec2(q.x, q.y), q.yaw);
114  // Init vel:
115  bb->SetLinearVelocity({0, 0});
116  bb->SetAngularVelocity(0);
117  }
118 
119  return b;
120 }
121 
123 {
124  MRPT_START
125 
126  // Sanity checks:
127  ASSERT_(0 == strcmp(node.name(), "walls"));
128 
129  std::string wallModelFileName;
130  std::string sTransformation;
131  double scale = 1.0;
132  mrpt::img::TColor wallColor{0x32, 0x32, 0x32, 0xff};
133  WallProperties wp;
134 
135  TParameterDefinitions params;
136  params["model_uri"] = TParamEntry("%s", &wallModelFileName);
137  params["transformation"] = TParamEntry("%s", &sTransformation);
138  params["wallThickness"] = TParamEntry("%lf", &wp.thickness);
139  params["wallHeight"] = TParamEntry("%lf", &wp.height);
140  params["scale"] = TParamEntry("%lf", &scale);
141  params["color"] = TParamEntry("%color", &wallColor);
142 
143  // Parse XML params:
144  parse_xmlnode_children_as_param(node, params, user_defined_variables());
145 
146  // Optional transformation:
147  auto HM = mrpt::math::CMatrixDouble44::Identity();
148  if (!sTransformation.empty())
149  {
150  std::stringstream ssError;
151  bool ok = HM.fromMatlabStringFormat(sTransformation, ssError);
152  if (!ok)
153  THROW_EXCEPTION_FMT(
154  "Error parsing 'transformation=\"%s\"' parameter of walls:\n%s",
155  sTransformation.c_str(), ssError.str().c_str());
156  MRPT_LOG_DEBUG_STREAM("Walls: using transformation: " << HM.asString());
157  }
158  const auto tf = mrpt::poses::CPose3D(HM);
159 
160  // Walls shape can come from external model file, or from a "shape" entry:
161  const auto* xml_shape = node.first_node("shape");
162 
163  // Final coordinates for wall perimeter are defined here:
164  std::vector<mrpt::math::TPoint3Df> tfPts;
165 
166  if (xml_shape)
167  {
168  // Load wall segments from "<shape>" tag.
169  mrpt::math::TPolygon2D segments;
170 
172  *xml_shape, segments, "[World::process_load_walls]");
173 
174  MRPT_LOG_DEBUG_STREAM(
175  "Walls loaded from <shape> tag, " << segments.size()
176  << " segments.");
177 
178  // Transform them:
179  tfPts.reserve(segments.size());
180  for (const auto& pt : segments) tfPts.emplace_back(tf.composePoint(pt));
181  }
182  else
183  {
184  // Load wall segments from external file.
185  ASSERT_(!wallModelFileName.empty());
186  const std::string localFileName =
187  xmlPathToActualPath(wallModelFileName);
188  ASSERT_FILE_EXISTS_(localFileName);
189 
190  MRPT_LOG_DEBUG_STREAM(
191  "Loading walls definition model from: " << localFileName);
192 
193  auto glModel = mrpt::opengl::CAssimpModel::Create();
194  glModel->loadScene(localFileName);
195 
196  const auto& points = glModel->shaderWireframeVertexPointBuffer();
197  MRPT_LOG_DEBUG_STREAM(
198  "Walls loaded from model file, " << points.size() << " segments.");
199 
200  // Transform them:
201  tfPts.reserve(points.size());
202  for (const auto& pt : points) tfPts.emplace_back(tf.composePoint(pt));
203  }
204 
205  // Insert all points for KD-tree lookup:
206  mrpt::maps::CSimplePointsMap ptsMap;
207 
208  // Create walls themselves:
209  ASSERT_(tfPts.size() % 2 == 0);
210  for (size_t i = 0; i < tfPts.size() / 2; i++)
211  {
212  const auto& pt1 = tfPts[i * 2 + 0];
213  const auto& pt2 = tfPts[i * 2 + 1];
214  auto block = create_wall_segment(this, pt1, pt2, wp, ptsMap);
215  block->block_color(wallColor);
216  insertBlock(block);
217  }
218 
219  MRPT_END
220 }
This file contains rapidxml parser and DOM implementation.
std::map< std::string, TParamEntry > TParameterDefinitions
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:224
std::unique_ptr< b2World > & getBox2DWorld()
Definition: World.h:297
Ch * name() const
Definition: rapidxml.hpp:673
geometry_msgs::TransformStamped t
A 2D column vector.
Definition: b2_math.h:41
std::shared_ptr< Block > Ptr
Definition: Block.h:37
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:936
static Block::Ptr create_wall_segment(World *parent, const mrpt::math::TPoint3D &rawEnd1, const mrpt::math::TPoint3D &rawEnd2, const WallProperties &wp, mrpt::maps::CSimplePointsMap &allPts)
Definition: World_walls.cpp:31
ROSCPP_DECL bool ok()
void parse_xmlnode_shape(const rapidxml::xml_node< char > &xml_node, mrpt::math::TPolygon2D &out_poly, const char *functionNameContext="")
Definition: xml_utils.cpp:271
This file contains rapidxml printer implementation.
void process_load_walls(const rapidxml::xml_node< char > &node)


mvsim
Author(s):
autogenerated on Tue Jul 4 2023 03:08:22