VehicleBase.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014 Jose Luis Blanco Claraco (University of Almeria) |
5  | Copyright (C) 2017 Borys Tymchenko (Odessa Polytechnic University) |
6  | Distributed under GNU General Public License version 3 |
7  | See <http://www.gnu.org/licenses/> |
8  +-------------------------------------------------------------------------+ */
9 
10 #include <mvsim/World.h>
11 #include <mvsim/VehicleBase.h>
16 #include <mvsim/FrictionModels/DefaultFriction.h> // For use as default model
17 
18 #include "JointXMLnode.h"
19 #include "XMLClassesRegistry.h"
20 #include "xml_utils.h"
21 
22 #include <rapidxml.hpp>
23 #include <rapidxml_utils.hpp>
24 #include <rapidxml_print.hpp>
25 #include <mrpt/poses/CPose2D.h>
26 #include <mrpt/opengl/CPolyhedron.h>
27 
28 #include <sstream> // std::stringstream
29 #include <map>
30 #include <string>
31 
32 using namespace mvsim;
33 using namespace std;
34 
36 
38 
39 // Explicit registration calls seem to be one (the unique?) way to assure
40 // registration takes place:
42 {
43  static bool done = false;
44  if (done)
45  return;
46  else
47  done = true;
48 
52  "ackermann_drivetrain", DynamicsAckermannDrivetrain)
53 }
54 
55 constexpr char VehicleBase::DL_TIMESTAMP[];
56 constexpr char VehicleBase::LOGGER_POSE[];
57 constexpr char VehicleBase::LOGGER_WHEEL[];
58 
59 constexpr char VehicleBase::PL_Q_X[];
60 constexpr char VehicleBase::PL_Q_Y[];
61 constexpr char VehicleBase::PL_Q_Z[];
62 constexpr char VehicleBase::PL_Q_YAW[];
63 constexpr char VehicleBase::PL_Q_PITCH[];
64 constexpr char VehicleBase::PL_Q_ROLL[];
65 constexpr char VehicleBase::PL_DQ_X[];
66 constexpr char VehicleBase::PL_DQ_Y[];
67 constexpr char VehicleBase::PL_DQ_Z[];
68 
69 constexpr char VehicleBase::WL_TORQUE[];
70 constexpr char VehicleBase::WL_WEIGHT[];
71 constexpr char VehicleBase::WL_VEL_X[];
72 constexpr char VehicleBase::WL_VEL_Y[];
73 constexpr char VehicleBase::WL_FRIC_X[];
74 constexpr char VehicleBase::WL_FRIC_Y[];
75 
76 // Protected ctor:
77 VehicleBase::VehicleBase(World* parent, size_t nWheels)
78  : VisualObject(parent),
79  m_vehicle_index(0),
80  m_b2d_vehicle_body(NULL),
81  m_q(0, 0, 0, 0, 0, 0),
82  m_dq(0, 0, 0),
83  m_chassis_mass(15.0),
84  m_chassis_z_min(0.05),
85  m_chassis_z_max(0.6),
86  m_chassis_color(0xff, 0x00, 0x00),
87  m_chassis_com(.0, .0),
88  m_wheels_info(nWheels),
89  m_fixture_wheels(nWheels, NULL)
90 {
91  using namespace mrpt::math;
92  // Default shape:
93  m_chassis_poly.push_back(TPoint2D(-0.4, -0.5));
94  m_chassis_poly.push_back(TPoint2D(-0.4, 0.5));
95  m_chassis_poly.push_back(TPoint2D(0.4, 0.5));
96  m_chassis_poly.push_back(TPoint2D(0.6, 0.3));
97  m_chassis_poly.push_back(TPoint2D(0.6, -0.3));
98  m_chassis_poly.push_back(TPoint2D(0.4, -0.5));
99  updateMaxRadiusFromPoly();
100 }
101 
103 {
104  if (m_b2d_vehicle_body)
105  {
106  // Pos:
107  const b2Vec2& pos = m_b2d_vehicle_body->GetPosition();
108  const float32 angle = m_b2d_vehicle_body->GetAngle();
109  m_q.x = pos(0);
110  m_q.y = pos(1);
111  m_q.yaw = angle;
112  // The rest (z,pitch,roll) will be always 0, unless other world-element
113  // modifies them! (e.g. elevation map)
114 
115  // Vel:
116  const b2Vec2& vel = m_b2d_vehicle_body->GetLinearVelocity();
117  const float32 w = m_b2d_vehicle_body->GetAngularVelocity();
118  m_dq.vals[0] = vel(0);
119  m_dq.vals[1] = vel(1);
120  m_dq.vals[2] = w;
121  }
122 }
123 
127  const rapidxml::xml_node<char>* xml_node)
128 {
129  // Sanity checks:
130  if (!xml_node)
131  throw runtime_error(
132  "[VehicleBase::register_vehicle_class] XML node is NULL");
133  if (0 != strcmp(xml_node->name(), "vehicle:class"))
134  throw runtime_error(
135  mrpt::format(
136  "[VehicleBase::register_vehicle_class] XML element is '%s' "
137  "('vehicle:class' expected)",
138  xml_node->name()));
139 
140  // rapidxml doesn't allow making copied of objects.
141  // So: convert to txt; then re-parse.
142  std::stringstream ss;
143  ss << *xml_node;
144 
145  veh_classes_registry.add(ss.str());
146 }
147 
151  World* parent, const rapidxml::xml_node<char>* root)
152 {
154 
155  using namespace std;
156  using namespace rapidxml;
157 
158  if (!root) throw runtime_error("[VehicleBase::factory] XML node is NULL");
159  if (0 != strcmp(root->name(), "vehicle"))
160  throw runtime_error(
161  mrpt::format(
162  "[VehicleBase::factory] XML root element is '%s' ('vehicle' "
163  "expected)",
164  root->name()));
165 
166  // "class": When a vehicle has a 'class="XXX"' attribute, look for each
167  // parameter
168  // in the set of "root" + "class_root" XML nodes:
169  // --------------------------------------------------------------------------------
170  JointXMLnode<> veh_root_node;
171  {
172  veh_root_node.add(
173  root); // Always search in root. Also in the class root, if any:
174 
175  const xml_attribute<>* veh_class = root->first_attribute("class");
176  if (veh_class)
177  {
178  const string sClassName = veh_class->value();
179  const rapidxml::xml_node<char>* class_root =
180  veh_classes_registry.get(sClassName);
181  if (!class_root)
182  throw runtime_error(
183  mrpt::format(
184  "[VehicleBase::factory] Vehicle class '%s' undefined",
185  sClassName.c_str()));
186 
187  veh_root_node.add(class_root);
188  // cout << *class_root;
189  }
190  }
191 
192  // Class factory according to: <dynamics class="XXX">
193  // -------------------------------------------------
194  const xml_node<>* dyn_node = veh_root_node.first_node("dynamics");
195  if (!dyn_node)
196  throw runtime_error(
197  "[VehicleBase::factory] Missing XML node <dynamics>");
198 
199  const xml_attribute<>* dyn_class = dyn_node->first_attribute("class");
200  if (!dyn_class || !dyn_class->value())
201  throw runtime_error(
202  "[VehicleBase::factory] Missing mandatory attribute 'class' in "
203  "node <dynamics>");
204 
205  VehicleBase* veh =
206  classFactory_vehicleDynamics.create(dyn_class->value(), parent);
207  if (!veh)
208  throw runtime_error(
209  mrpt::format(
210  "[VehicleBase::factory] Unknown vehicle dynamics class '%s'",
211  dyn_class->value()));
212 
213  // Initialize here all common params shared by any polymorphic class:
214  // -------------------------------------------------
215  // attrib: name
216  {
217  const xml_attribute<>* attrib_name = root->first_attribute("name");
218  if (attrib_name && attrib_name->value())
219  {
220  veh->m_name = attrib_name->value();
221  }
222  else
223  {
224  // Default name:
225  static int cnt = 0;
226  veh->m_name = mrpt::format("veh%i", ++cnt);
227  }
228  }
229 
230  // (Mandatory) initial pose:
231  {
232  const xml_node<>* node = veh_root_node.first_node("init_pose");
233  if (!node)
234  throw runtime_error(
235  "[VehicleBase::factory] Missing XML node <init_pose>");
236 
237  if (3 != ::sscanf(
238  node->value(), "%lf %lf %lf", &veh->m_q.x, &veh->m_q.y,
239  &veh->m_q.yaw))
240  throw runtime_error(
241  "[VehicleBase::factory] Error parsing "
242  "<init_pose>...</init_pose>");
243  veh->m_q.yaw *= M_PI / 180.0; // deg->rad
244  }
245 
246  // (Optional) initial vel:
247  {
248  const xml_node<>* node = veh_root_node.first_node("init_vel");
249  if (node)
250  {
251  if (3 != ::sscanf(
252  node->value(), "%lf %lf %lf", &veh->m_dq.vals[0],
253  &veh->m_dq.vals[1], &veh->m_dq.vals[2]))
254  throw runtime_error(
255  "[VehicleBase::factory] Error parsing "
256  "<init_vel>...</init_vel>");
257  veh->m_dq.vals[2] *= M_PI / 180.0; // deg->rad
258 
259  // Convert twist (velocity) from local -> global coords:
260  const mrpt::poses::CPose2D pose(
261  0, 0, veh->m_q.yaw); // Only the rotation
262  pose.composePoint(
263  veh->m_dq.vals[0], veh->m_dq.vals[1], veh->m_dq.vals[0],
264  veh->m_dq.vals[1]);
265  }
266  }
267 
268  // Initialize class-specific params:
269  // -------------------------------------------------
270  veh->dynamics_load_params_from_xml(dyn_node);
271 
272  // <Optional> Log path. If not specified, app folder will be used
273  // -----------------------------------------------------------
274  {
275  const xml_node<>* log_path_node = veh_root_node.first_node("log_path");
276  if (log_path_node)
277  {
278  // Parse:
279  veh->m_log_path = log_path_node->value();
280  }
281  }
282 
283  veh->initLoggers();
284 
285  // Register bodies, fixtures, etc. in Box2D simulator:
286  // ----------------------------------------------------
287  b2World* b2world = parent->getBox2DWorld();
288  veh->create_multibody_system(b2world);
289 
290  if (veh->m_b2d_vehicle_body)
291  {
292  // Init pos:
293  veh->m_b2d_vehicle_body->SetTransform(
294  b2Vec2(veh->m_q.x, veh->m_q.y), veh->m_q.yaw);
295  // Init vel:
296  veh->m_b2d_vehicle_body->SetLinearVelocity(
297  b2Vec2(veh->m_dq.vals[0], veh->m_dq.vals[1]));
298  veh->m_b2d_vehicle_body->SetAngularVelocity(veh->m_dq.vals[2]);
299  }
300 
301  // Friction model:
302  // Parse <friction> node, or assume default linear model:
303  // -----------------------------------------------------------
304  {
305  const xml_node<>* frict_node = veh_root_node.first_node("friction");
306  if (!frict_node)
307  {
308  // Default:
309  veh->m_friction = std::shared_ptr<FrictionBase>(
310  new DefaultFriction(*veh, NULL /*default params*/));
311  }
312  else
313  {
314  // Parse:
315  veh->m_friction = std::shared_ptr<FrictionBase>(
316  FrictionBase::factory(*veh, frict_node));
317  ASSERT_(veh->m_friction);
318  }
319  }
320 
321  // Sensors: <sensor class='XXX'> entries
322  // -------------------------------------------------
323  for (JointXMLnode<>::iterator it = veh_root_node.begin();
324  it != veh_root_node.end(); ++it)
325  {
326  if (!strcmp(it->name(), "sensor"))
327  {
328  SensorBase* se = SensorBase::factory(*veh, *it);
329  veh->m_sensors.push_back(SensorBase::Ptr(se));
330  }
331  }
332 
333  return veh;
334 }
335 
336 VehicleBase* VehicleBase::factory(World* parent, const std::string& xml_text)
337 {
338  // Parse the string as if it was an XML file:
339  std::stringstream s;
340  s.str(xml_text);
341 
342  char* input_str = const_cast<char*>(xml_text.c_str());
344  try
345  {
346  xml.parse<0>(input_str);
347  }
348  catch (rapidxml::parse_error& e)
349  {
350  unsigned int line =
351  static_cast<long>(std::count(input_str, e.where<char>(), '\n') + 1);
352  throw std::runtime_error(
353  mrpt::format(
354  "[VehicleBase::factory] XML parse error (Line %u): %s",
355  static_cast<unsigned>(line), e.what()));
356  }
357  return VehicleBase::factory(parent, xml.first_node());
358 }
359 
361 {
362  // Update wheels position (they may turn, etc. as in an Ackermann
363  // configuration)
364  for (size_t i = 0; i < m_fixture_wheels.size(); i++)
365  {
366  b2PolygonShape* wheelShape =
367  dynamic_cast<b2PolygonShape*>(m_fixture_wheels[i]->GetShape());
368  wheelShape->SetAsBox(
369  m_wheels_info[i].diameter * 0.5, m_wheels_info[i].width * 0.5,
370  b2Vec2(m_wheels_info[i].x, m_wheels_info[i].y),
371  m_wheels_info[i].yaw);
372  }
373 
374  // Apply motor forces/torques:
375  this->invoke_motor_controllers(context, m_torque_per_wheel);
376 
377  // Apply friction model at each wheel:
378  const size_t nW = getNumWheels();
379  ASSERT_EQUAL_(m_torque_per_wheel.size(), nW);
380 
381  const double gravity = getWorldObject()->get_gravity();
382  const double massPerWheel =
383  getChassisMass() / nW; // Part of the vehicle weight on each wheel.
384  const double weightPerWheel = massPerWheel * gravity;
385 
386  std::vector<mrpt::math::TPoint2D> wheels_vels;
388 
389  ASSERT_EQUAL_(wheels_vels.size(), nW);
390 
391  std::vector<mrpt::math::TSegment3D>
392  force_vectors; // For visualization only
393 
394  for (size_t i = 0; i < nW; i++)
395  {
396  // prepare data:
397  Wheel& w = getWheelInfo(i);
398 
399  FrictionBase::TFrictionInput fi(context, w);
400  fi.motor_torque =
401  -m_torque_per_wheel[i]; // "-" => Forwards is negative
402  fi.weight = weightPerWheel;
403  fi.wheel_speed = wheels_vels[i];
404 
405  m_friction->setLogger(
406  getLoggerPtr(LOGGER_WHEEL + std::to_string(i + 1)));
407  // eval friction:
408  mrpt::math::TPoint2D net_force_;
409  m_friction->evaluate_friction(fi, net_force_);
410 
411  // Apply force:
412  const b2Vec2 wForce = m_b2d_vehicle_body->GetWorldVector(
413  b2Vec2(
414  net_force_.x, net_force_.y)); // Force vector -> world coords
415  const b2Vec2 wPt = m_b2d_vehicle_body->GetWorldPoint(
416  b2Vec2(w.x, w.y)); // Application point -> world coords
417  // printf("w%i: Lx=%6.3f Ly=%6.3f | Gx=%11.9f
418  // Gy=%11.9f\n",(int)i,net_force_.x,net_force_.y,wForce.x,wForce.y);
419 
420  m_b2d_vehicle_body->ApplyForce(wForce, wPt, true /*wake up*/);
421 
422  // log
423  {
424  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
425  DL_TIMESTAMP, context.simul_time);
426  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
427  WL_TORQUE, fi.motor_torque);
428  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
429  WL_WEIGHT, fi.weight);
430  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
431  WL_VEL_X, fi.wheel_speed.x);
432  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
433  WL_VEL_Y, fi.wheel_speed.y);
434  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
435  WL_FRIC_X, net_force_.x);
436  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->updateColumn(
437  WL_FRIC_Y, net_force_.y);
438  }
439 
440  // save it for optional rendering:
442  {
443  const double forceScale =
444  m_world->m_gui_options.force_scale; // [meters/N]
445  const mrpt::math::TPoint3D pt1(
446  wPt.x, wPt.y, m_chassis_z_max * 1.1 + m_q.z);
447  const mrpt::math::TPoint3D pt2 =
448  pt1 + mrpt::math::TPoint3D(wForce.x, wForce.y, 0) * forceScale;
449  force_vectors.push_back(mrpt::math::TSegment3D(pt1, pt2));
450  }
451  }
452 
453  // Save forces for optional rendering:
455  {
456  std::lock_guard<std::mutex> csl(m_force_segments_for_rendering_cs);
457  m_force_segments_for_rendering = force_vectors;
458  }
459 }
460 
464 {
465  // Integrate wheels' rotation:
466  const size_t nW = getNumWheels();
467 
468  for (size_t i = 0; i < nW; i++)
469  {
470  // prepare data:
471  Wheel& w = getWheelInfo(i);
472 
473  // Explicit Euler:
474  w.setPhi(w.getPhi() + w.getW() * context.dt);
475 
476  // Wrap wheel spin position (angle), so it doesn't
477  // become excessively large (it's actually unbound, but we don't want to
478  // lose 'double' accuracy):
479  const double cur_abs_phi = std::abs(w.getPhi());
480  if (cur_abs_phi > 1e4)
481  w.setPhi(
482  ::fmod(cur_abs_phi, 2 * M_PI) *
483  (w.getPhi() < 0.0 ? -1.0 : 1.0));
484  }
485 
486  m_loggers[LOGGER_POSE]->updateColumn(DL_TIMESTAMP, context.simul_time);
487  m_loggers[LOGGER_POSE]->updateColumn(PL_Q_X, m_q.x);
488  m_loggers[LOGGER_POSE]->updateColumn(PL_Q_Y, m_q.y);
489  m_loggers[LOGGER_POSE]->updateColumn(PL_Q_Z, m_q.z);
490  m_loggers[LOGGER_POSE]->updateColumn(PL_Q_YAW, m_q.yaw);
491  m_loggers[LOGGER_POSE]->updateColumn(PL_Q_PITCH, m_q.pitch);
492  m_loggers[LOGGER_POSE]->updateColumn(PL_Q_ROLL, m_q.roll);
493  m_loggers[LOGGER_POSE]->updateColumn(PL_DQ_X, m_dq.vals[0]);
494  m_loggers[LOGGER_POSE]->updateColumn(PL_DQ_Y, m_dq.vals[1]);
495  m_loggers[LOGGER_POSE]->updateColumn(PL_DQ_Z, m_dq.vals[2]);
496 
497  {
498  writeLogStrings();
499  }
500 }
501 
504  std::vector<mrpt::math::TPoint2D>& vels, const vec3& veh_vel_local) const
505 {
506  // Each wheel velocity is:
507  // v_w = v_veh + \omega \times wheel_pos
508  // =>
509  // v_w = v_veh + ( -w*y, w*x )
510 
511  const double w = veh_vel_local.vals[2]; // vehicle w
512 
513  const size_t nW = this->getNumWheels();
514  vels.resize(nW);
515  for (size_t i = 0; i < nW; i++)
516  {
517  const Wheel& wheel = getWheelInfo(i);
518 
519  vels[i].x = veh_vel_local.vals[0] - w * wheel.y;
520  vels[i].y = veh_vel_local.vals[1] + w * wheel.x;
521  }
522 }
523 
526 {
527  vec3 local_vel;
528  local_vel.vals[2] = m_dq.vals[2]; // omega remains the same.
529 
530  const mrpt::poses::CPose2D p(0, 0, -m_q.yaw); // "-" means inverse pose
531  p.composePoint(
532  m_dq.vals[0], m_dq.vals[1], local_vel.vals[0], local_vel.vals[1]);
533  return local_vel;
534 }
535 
536 mrpt::poses::CPose2D VehicleBase::getCPose2D() const
537 {
538  return mrpt::poses::CPose2D(mrpt::math::TPose2D(m_q));
539 }
540 
543  mrpt::opengl::COpenGLScene& scene, bool defaultVehicleBody)
544 {
545  // 1st time call?? -> Create objects
546  // ----------------------------------
547  if (defaultVehicleBody)
548  {
549  const size_t nWs = this->getNumWheels();
550  if (!m_gl_chassis)
551  {
552  m_gl_chassis = mrpt::opengl::CSetOfObjects::Create();
553 
554  // Wheels shape:
555  m_gl_wheels.resize(nWs);
556  for (size_t i = 0; i < nWs; i++)
557  {
558  m_gl_wheels[i] = mrpt::opengl::CSetOfObjects::Create();
559  this->getWheelInfo(i).getAs3DObject(*m_gl_wheels[i]);
560  m_gl_chassis->insert(m_gl_wheels[i]);
561  }
562  // Robot shape:
563  mrpt::opengl::CPolyhedron::Ptr gl_poly =
564  mrpt::opengl::CPolyhedron::CreateCustomPrism(
565  m_chassis_poly, m_chassis_z_max - m_chassis_z_min);
566  gl_poly->setLocation(0, 0, m_chassis_z_min);
567  gl_poly->setColor(TColorf(m_chassis_color));
568  m_gl_chassis->insert(gl_poly);
569 
570  SCENE_INSERT_Z_ORDER(scene, 1, m_gl_chassis);
571 
572  // Visualization of forces:
573  m_gl_forces = mrpt::opengl::CSetOfLines::Create();
574  m_gl_forces->setLineWidth(3.0);
575  m_gl_forces->setColor_u8(TColor(0xff, 0xff, 0xff));
576 
578  scene, 3, m_gl_forces); // forces are in global coords
579  }
580 
581  // Update them:
582  // ----------------------------------
583  m_gl_chassis->setPose(m_q);
584 
585  for (size_t i = 0; i < nWs; i++)
586  {
587  const Wheel& w = getWheelInfo(i);
588  m_gl_wheels[i]->setPose(
589  mrpt::math::TPose3D(
590  w.x, w.y, 0.5 * w.diameter, w.yaw, w.getPhi(), 0.0));
591  }
592  }
593 
594  // Other common stuff:
595  internal_gui_update_sensors(scene);
596  internal_gui_update_forces(scene);
597 }
598 
599 void VehicleBase::internal_gui_update_sensors(mrpt::opengl::COpenGLScene& scene)
600 {
601  for (TListSensors::iterator it = m_sensors.begin(); it != m_sensors.end();
602  ++it)
603  (*it)->gui_update(scene);
604 }
605 
606 void VehicleBase::internal_gui_update_forces(mrpt::opengl::COpenGLScene& scene)
607 {
609  {
610  std::lock_guard<std::mutex> csl(m_force_segments_for_rendering_cs);
611  m_gl_forces->clear();
612  m_gl_forces->appendLines(m_force_segments_for_rendering);
613  m_gl_forces->setVisibility(true);
614  }
615  else
616  {
617  m_gl_forces->setVisibility(false);
618  }
619 }
620 
621 void VehicleBase::updateMaxRadiusFromPoly()
622 {
623  using namespace mrpt::math;
624 
625  m_max_radius = 0.001f;
626  for (TPolygon2D::const_iterator it = m_chassis_poly.begin();
627  it != m_chassis_poly.end(); ++it)
628  {
629  const float n = it->norm();
630  keep_max(m_max_radius, n);
631  }
632 }
633 
636 {
637  // Define the dynamic body. We set its position and call the body factory.
638  b2BodyDef bodyDef;
639  bodyDef.type = b2_dynamicBody;
640 
641  m_b2d_vehicle_body = world->CreateBody(&bodyDef);
642 
643  // Define shape of chassis:
644  // ------------------------------
645  {
646  // Convert shape into Box2D format:
647  const size_t nPts = m_chassis_poly.size();
648  ASSERT_(nPts >= 3);
649  ASSERT_BELOWEQ_(nPts, (size_t)b2_maxPolygonVertices);
650  std::vector<b2Vec2> pts(nPts);
651  for (size_t i = 0; i < nPts; i++)
652  pts[i] = b2Vec2(m_chassis_poly[i].x, m_chassis_poly[i].y);
653 
654  b2PolygonShape chassisPoly;
655  chassisPoly.Set(&pts[0], nPts);
656  // chassisPoly.m_radius = 1e-3; // The "skin" depth of the body
657 
658  // Define the dynamic body fixture.
659  b2FixtureDef fixtureDef;
660  fixtureDef.shape = &chassisPoly;
661  fixtureDef.restitution = 0.01;
662 
663  // Set the box density to be non-zero, so it will be dynamic.
664  b2MassData mass;
665  chassisPoly.ComputeMass(
666  &mass, 1); // Mass with density=1 => compute area
667  fixtureDef.density = m_chassis_mass / mass.mass;
668 
669  // Override the default friction.
670  fixtureDef.friction = 0.3f;
671 
672  // Add the shape to the body.
673  m_fixture_chassis = m_b2d_vehicle_body->CreateFixture(&fixtureDef);
674 
675  // Compute center of mass:
676  b2MassData vehMass;
677  m_fixture_chassis->GetMassData(&vehMass);
678  m_chassis_com.x = vehMass.center.x;
679  m_chassis_com.y = vehMass.center.y;
680  }
681 
682  // Define shape of wheels:
683  // ------------------------------
684  ASSERT_EQUAL_(m_fixture_wheels.size(), m_wheels_info.size());
685 
686  for (size_t i = 0; i < m_wheels_info.size(); i++)
687  {
688  b2PolygonShape wheelShape;
689  wheelShape.SetAsBox(
690  m_wheels_info[i].diameter * 0.5, m_wheels_info[i].width * 0.5,
691  b2Vec2(m_wheels_info[i].x, m_wheels_info[i].y),
692  m_wheels_info[i].yaw);
693 
694  // Define the dynamic body fixture.
695  b2FixtureDef fixtureDef;
696  fixtureDef.shape = &wheelShape;
697  fixtureDef.restitution = 0.05;
698 
699  // Set the box density to be non-zero, so it will be dynamic.
700  b2MassData mass;
701  wheelShape.ComputeMass(
702  &mass, 1); // Mass with density=1 => compute area
703  fixtureDef.density = m_wheels_info[i].mass / mass.mass;
704 
705  // Override the default friction.
706  fixtureDef.friction = 0.5f;
707 
708  m_fixture_wheels[i] = m_b2d_vehicle_body->CreateFixture(&fixtureDef);
709  }
710 }
711 
712 void VehicleBase::gui_update(mrpt::opengl::COpenGLScene& scene)
713 {
714  this->gui_update_common(scene); // Common part: update sensors, etc.
715 }
716 
718 {
719  m_loggers[LOGGER_POSE] = std::make_shared<CSVLogger>();
720  // m_loggers[LOGGER_POSE]->addColumn(DL_TIMESTAMP);
721  // m_loggers[LOGGER_POSE]->addColumn(PL_Q_X);
722  // m_loggers[LOGGER_POSE]->addColumn(PL_Q_Y);
723  // m_loggers[LOGGER_POSE]->addColumn(PL_Q_Z);
724  // m_loggers[LOGGER_POSE]->addColumn(PL_Q_YAW);
725  // m_loggers[LOGGER_POSE]->addColumn(PL_Q_PITCH);
726  // m_loggers[LOGGER_POSE]->addColumn(PL_Q_ROLL);
727  // m_loggers[LOGGER_POSE]->addColumn(PL_DQ_X);
728  // m_loggers[LOGGER_POSE]->addColumn(PL_DQ_Y);
729  // m_loggers[LOGGER_POSE]->addColumn(PL_DQ_Z);
730  m_loggers[LOGGER_POSE]->setFilepath(
731  m_log_path + "mvsim_" + m_name + LOGGER_POSE + ".log");
732 
733  for (size_t i = 0; i < getNumWheels(); i++)
734  {
735  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)] =
736  std::make_shared<CSVLogger>();
737  // m_loggers[LOGGER_WHEEL + std::to_string(i +
738  // 1)]->addColumn(DL_TIMESTAMP);
739  // m_loggers[LOGGER_WHEEL + std::to_string(i +
740  // 1)]->addColumn(WL_TORQUE);
741  // m_loggers[LOGGER_WHEEL + std::to_string(i +
742  // 1)]->addColumn(WL_WEIGHT);
743  // m_loggers[LOGGER_WHEEL + std::to_string(i +
744  // 1)]->addColumn(WL_VEL_X);
745  // m_loggers[LOGGER_WHEEL + std::to_string(i +
746  // 1)]->addColumn(WL_VEL_Y);
747  // m_loggers[LOGGER_WHEEL + std::to_string(i +
748  // 1)]->addColumn(WL_FRIC_X);
749  // m_loggers[LOGGER_WHEEL + std::to_string(i +
750  // 1)]->addColumn(WL_FRIC_Y);
751  m_loggers[LOGGER_WHEEL + std::to_string(i + 1)]->setFilepath(
752  m_log_path + "mvsim_" + m_name + LOGGER_WHEEL +
753  std::to_string(i + 1) + ".log");
754  }
755 }
756 
758 {
759  std::map<std::string, std::shared_ptr<CSVLogger>>::iterator it;
760  for (it = m_loggers.begin(); it != m_loggers.end(); ++it)
761  {
762  it->second->writeRow();
763  }
764 }
765 
767  double fx, double fy, double local_ptx, double local_pty)
768 {
769  ASSERT_(m_b2d_vehicle_body);
770  const b2Vec2 wPt = m_b2d_vehicle_body->GetWorldPoint(
771  b2Vec2(local_ptx, local_pty)); // Application point -> world coords
772  m_b2d_vehicle_body->ApplyForce(b2Vec2(fx, fy), wPt, true /*wake up*/);
773 }
const b2Shape * shape
Definition: b2Fixture.h:71
double force_scale
In meters/Newton.
Definition: World.h:255
This file contains rapidxml parser and DOM implementation.
virtual void create_multibody_system(b2World *world)
Ch * where() const
Definition: rapidxml.hpp:94
Ch * value() const
Definition: rapidxml.hpp:692
void getWheelsVelocityLocal(std::vector< mrpt::math::TPoint2D > &vels, const vec3 &veh_vel_local) const
XmlRpcServer s
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)=0
double simul_time
Current time in the simulated world.
Definition: basic_types.h:56
#define REGISTER_VEHICLE_DYNAMICS(TEXTUAL_NAME, CLASS_NAME)
Definition: VehicleBase.h:299
double vals[3]
Definition: basic_types.h:64
virtual void initLoggers()
void parse(Ch *text)
Definition: rapidxml.hpp:1381
virtual void apply_force(double fx, double fy, double local_ptx=0.0, double local_pty=0.0)
void getAs3DObject(mrpt::opengl::CSetOfObjects &obj)
Definition: Wheel.cpp:50
std::shared_ptr< CSVLogger > getLoggerPtr(std::string logger_name)
Definition: VehicleBase.h:133
b2Vec2 center
The position of the shape&#39;s centroid relative to the shape&#39;s origin.
Definition: b2Shape.h:33
TFSIMD_FORCE_INLINE const tfScalar & y() const
virtual void simul_post_timestep(const TSimulContext &context)
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:936
std::string m_log_path
Definition: VehicleBase.h:176
A 2D column vector.
Definition: b2Math.h:53
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double get_gravity() const
Definition: World.h:113
double x
Definition: Wheel.h:41
TClassFactory_vehicleDynamics classFactory_vehicleDynamics
Definition: VehicleBase.cpp:37
static FrictionBase * factory(VehicleBase &parent, const rapidxml::xml_node< char > *xml_node)
size_t getNumWheels() const
Definition: VehicleBase.h:92
b2BodyType type
Definition: b2Body.h:74
double dt
timestep
Definition: basic_types.h:57
void ComputeMass(b2MassData *massData, float32 density) const
float32 mass
The mass of the shape, usually in kilograms.
Definition: b2Shape.h:30
VehicleBase(World *parent, size_t nWheels)
Definition: VehicleBase.cpp:77
World * getWorldObject()
Definition: VisualObject.h:29
CLASS * create(const std::string &class_name, ARG1 a1) const
Definition: ClassFactory.h:36
void setPhi(double val)
Orientation (rad) wrt vehicle local frame.
Definition: Wheel.h:58
double getW() const
Spinning velocity (rad/s) wrt shaft.
Definition: Wheel.h:62
#define SCENE_INSERT_Z_ORDER(_SCENE, _ZORDER_INDEX, _OBJ_TO_INSERT)
Definition: VisualObject.h:37
Ch * name() const
Definition: rapidxml.hpp:673
double y
Definition: Wheel.h:41
std::shared_ptr< SensorBase > Ptr
Definition: SensorBase.h:23
virtual void simul_pre_timestep(const TSimulContext &context)
TGUI_Options m_gui_options
Definition: World.h:265
double diameter
[m,rad] (in local coords)
Definition: Wheel.h:43
virtual const char * what() const
Definition: rapidxml.hpp:85
xml_attribute< Ch > * first_attribute(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:1025
#define b2_maxPolygonVertices
Definition: b2Settings.h:54
static void register_vehicle_class(const rapidxml::xml_node< char > *xml_node)
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::map< std::string, std::shared_ptr< CSVLogger > > m_loggers
Definition: VehicleBase.h:175
float32 density
The density, usually in kg/m^2.
Definition: b2Fixture.h:83
const Wheel & getWheelInfo(const size_t idx) const
Definition: VehicleBase.h:93
double yaw
Definition: Wheel.h:41
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel)=0
void SetAsBox(float32 hx, float32 hy)
double getPhi() const
Orientation (rad) wrt vehicle local frame.
Definition: Wheel.h:54
void gui_update_common(mrpt::opengl::COpenGLScene &scene, bool defaultVehicleBody=true)
const rapidxml::xml_node< Ch > * first_node(const char *name)
Definition: JointXMLnode.h:28
float32 y
Definition: b2Math.h:140
virtual void gui_update(mrpt::opengl::COpenGLScene &scene)
TFSIMD_FORCE_INLINE const tfScalar & w() const
void Set(const b2Vec2 *points, int32 count)
virtual void writeLogStrings()
mrpt::math::TPoint2D wheel_speed
Definition: FrictionBase.h:40
double motor_torque
(Newtons), excluding the weight of the wheel itself.
Definition: FrictionBase.h:37
float32 restitution
The restitution (elasticity) usually in the range [0,1].
Definition: b2Fixture.h:80
void simul_post_timestep_common(const TSimulContext &context)
const rapidxml::xml_node< char > * get(const std::string &xml_node_class) const
static SensorBase * factory(VehicleBase &parent, const rapidxml::xml_node< char > *xml_node)
Definition: SensorBase.cpp:52
b2World * getBox2DWorld()
Definition: World.h:178
This file contains rapidxml printer implementation.
mrpt::poses::CPose2D getCPose2D() const
void add(const std::string &input_xml_node_class)
float32 x
Definition: b2Math.h:140
void register_all_veh_dynamics()
Definition: VehicleBase.cpp:41
XmlClassesRegistry veh_classes_registry("vehicle:class")
vec3 getVelocityLocal() const
This holds the mass data computed for a shape.
Definition: b2Shape.h:27
void add(const rapidxml::xml_node< Ch > *node)
Definition: JointXMLnode.h:27
float32 friction
The friction coefficient, usually in the range [0,1].
Definition: b2Fixture.h:77
virtual double getChassisMass() const
Definition: VehicleBase.h:85
b2Body * CreateBody(const b2BodyDef *def)
Definition: b2World.cpp:107
float float32
Definition: b2Settings.h:35
std::string m_name
User-supplied name of the vehicle (e.g. "r1", "veh1")
Definition: VehicleBase.h:205
static VehicleBase * factory(World *parent, const rapidxml::xml_node< char > *xml_node)


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 19:36:40