VehicleAckermann_Drivetrain.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>
12 #include <mvsim/World.h>
13 
14 #include <cmath>
15 #include <rapidxml.hpp>
16 
17 #include "xml_utils.h"
18 
19 using namespace mvsim;
20 using namespace std;
21 
22 // Ctor:
24  : VehicleBase(parent, 4 /*num wheels*/), max_steer_ang_(mrpt::DEG2RAD(30))
25 {
26  using namespace mrpt::math;
27 
28  chassis_mass_ = 500.0;
29  chassis_z_min_ = 0.20;
30  chassis_z_max_ = 1.40;
31  chassis_color_ = mrpt::img::TColor(0xe8, 0x30, 0x00);
32 
33  // Default shape:
34  chassis_poly_.clear();
35  chassis_poly_.emplace_back(-0.8, -1.0);
36  chassis_poly_.emplace_back(-0.8, 1.0);
37  chassis_poly_.emplace_back(1.5, 0.9);
38  chassis_poly_.emplace_back(1.8, 0.8);
39  chassis_poly_.emplace_back(1.8, -0.8);
40  chassis_poly_.emplace_back(1.5, -0.9);
42 
43  fixture_chassis_ = nullptr;
44  for (int i = 0; i < 4; i++) fixture_wheels_[i] = nullptr;
45 
46  // Default values:
47  // rear-left:
48  wheels_info_[WHEEL_RL].x = 0;
49  wheels_info_[WHEEL_RL].y = 0.9;
50  // rear-right:
51  wheels_info_[WHEEL_RR].x = 0;
52  wheels_info_[WHEEL_RR].y = -0.9;
53  // Front-left:
54  wheels_info_[WHEEL_FL].x = 1.3;
55  wheels_info_[WHEEL_FL].y = 0.9;
56  // Front-right:
57  wheels_info_[WHEEL_FR].x = 1.3;
58  wheels_info_[WHEEL_FR].y = -0.9;
59 
60  FrontRearSplit_ = 0.5;
61  FrontLRSplit_ = 0.5;
62  RearLRSplit_ = 0.5;
63 
64  FrontRearBias_ = 1.5;
65  FrontLRBias_ = 1.5;
66  RearLRBias_ = 1.5;
67 
69 }
70 
73  const rapidxml::xml_node<char>* xml_node)
74 {
75  // <chassis ...> </chassis>
76  const rapidxml::xml_node<char>* xml_chassis = xml_node->first_node("chassis");
77  if (xml_chassis)
78  {
79  // Attribs:
80  TParameterDefinitions attribs;
81  attribs["mass"] = TParamEntry("%lf", &this->chassis_mass_);
82  attribs["zmin"] = TParamEntry("%lf", &this->chassis_z_min_);
83  attribs["zmax"] = TParamEntry("%lf", &this->chassis_z_max_);
84  attribs["color"] = TParamEntry("%color", &this->chassis_color_);
85 
87  *xml_chassis, attribs, {},
88  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
89 
90  // Shape node (optional, fallback to default shape if none found)
91  const rapidxml::xml_node<char>* xml_shape = xml_chassis->first_node("shape");
92  if (xml_shape)
94  *xml_shape, chassis_poly_,
95  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
96  }
97 
98  //<rl_wheel pos="0 1" mass="6.0" width="0.30" diameter="0.62" />
99  //<rr_wheel pos="0 -1" mass="6.0" width="0.30" diameter="0.62" />
100  //<fl_wheel mass="6.0" width="0.30" diameter="0.62" />
101  //<fr_wheel mass="6.0" width="0.30" diameter="0.62" />
102  const char* w_names[4] = {
103  "rl_wheel", // 0
104  "rr_wheel", // 1
105  "fl_wheel", // 2
106  "fr_wheel" // 3
107  };
108  // Load common params:
109  for (size_t i = 0; i < 4; i++)
110  {
111  if (auto xml_wheel = xml_node->first_node(w_names[i]); xml_wheel)
112  {
113  wheels_info_[i].loadFromXML(xml_wheel);
114  }
115  else
116  {
117  world_->logFmt(
118  mrpt::system::LVL_WARN, "No XML entry '%s' found: using defaults for wheel #%u",
119  w_names[i], static_cast<unsigned int>(i));
120  }
121  }
122 
123  //<f_wheels_x>1.3</f_wheels_x>
124  //<f_wheels_d>2.0</f_wheels_d>
125  // Load front ackermann wheels and other params:
126  {
127  double front_x = 1.3;
128  double front_d = 2.0;
129  TParameterDefinitions ack_ps;
130  // Front wheels:
131  ack_ps["f_wheels_x"] = TParamEntry("%lf", &front_x);
132  ack_ps["f_wheels_d"] = TParamEntry("%lf", &front_d);
133  // other params:
134  ack_ps["max_steer_ang_deg"] = TParamEntry("%lf_deg", &max_steer_ang_);
135 
137  *xml_node, ack_ps, {}, "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
138 
139  // Front-left:
140  wheels_info_[WHEEL_FL].x = front_x;
141  wheels_info_[WHEEL_FL].y = 0.5 * front_d;
142  // Front-right:
143  wheels_info_[WHEEL_FR].x = front_x;
144  wheels_info_[WHEEL_FR].y = -0.5 * front_d;
145  }
146 
147  // Drivetrain parameters
148  // Watch the order of DifferentialType enum!
149  const char* drive_names[6] = {"open_front", "open_rear", "open_4wd",
150  "torsen_front", "torsen_rear", "torsen_4wd"};
151 
152  const rapidxml::xml_node<char>* xml_drive = xml_node->first_node("drivetrain");
153  if (xml_drive)
154  {
155  TParameterDefinitions attribs;
156  std::string diff_type;
157  attribs["type"] = TParamEntry("%s", &diff_type);
158 
160  *xml_drive, attribs, {},
161  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
162 
163  for (size_t i = 0; i < DifferentialType::DIFF_MAX; ++i)
164  {
165  if (diff_type == drive_names[i])
166  {
168  break;
169  }
170  }
171 
172  TParameterDefinitions drive_params;
173  drive_params["front_rear_split"] = TParamEntry("%lf", &FrontRearSplit_);
174  drive_params["front_rear_bias"] = TParamEntry("%lf", &FrontRearBias_);
175  drive_params["front_left_right_split"] = TParamEntry("%lf", &FrontLRSplit_);
176  drive_params["front_left_right_bias"] = TParamEntry("%lf", &FrontLRBias_);
177  drive_params["rear_left_right_split"] = TParamEntry("%lf", &RearLRSplit_);
178  drive_params["rear_left_right_bias"] = TParamEntry("%lf", &RearLRBias_);
179 
181  *xml_drive, drive_params, {},
182  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
183  }
184 
185  // Vehicle controller:
186  // -------------------------------------------------
187  {
188  const rapidxml::xml_node<char>* xml_control = xml_node->first_node("controller");
189  if (xml_control)
190  {
191  rapidxml::xml_attribute<char>* control_class = xml_control->first_attribute("class");
192  if (!control_class || !control_class->value())
193  throw runtime_error(
194  "[DynamicsAckermannDrivetrain] Missing 'class' attribute "
195  "in <controller> XML node");
196 
197  const std::string sCtrlClass = std::string(control_class->value());
198  if (sCtrlClass == ControllerRawForces::class_name())
199  controller_ = std::make_shared<ControllerRawForces>(*this);
200  else if (sCtrlClass == ControllerTwistFrontSteerPID::class_name())
201  controller_ = std::make_shared<ControllerTwistFrontSteerPID>(*this);
202  else if (sCtrlClass == ControllerFrontSteerPID::class_name())
203  controller_ = std::make_shared<ControllerFrontSteerPID>(*this);
204  else
205  THROW_EXCEPTION_FMT(
206  "[DynamicsAckermannDrivetrain] Unknown 'class'='%s' in "
207  "<controller> XML node",
208  sCtrlClass.c_str());
209 
210  controller_->load_config(*xml_control);
211  }
212  }
213 
214  // Default controller:
215  if (!controller_) controller_ = std::make_shared<ControllerRawForces>(*this);
216 }
217 
218 // See docs in base class:
220  const TSimulContext& context)
221 {
222  // Longitudinal forces at each wheel:
223  std::vector<double> out_torque_per_wheel;
224  out_torque_per_wheel.assign(4, 0.0);
225  double torque_split_per_wheel[4] = {0.0};
226 
227  if (controller_)
228  {
229  // Invoke controller:
230  TControllerInput ci;
231  ci.context = context;
233  controller_->control_step(ci, co);
234  // Take its output:
235 
236  switch (diff_type_)
237  {
238  case DIFF_OPEN_FRONT:
239  {
240  torque_split_per_wheel[WHEEL_FL] = FrontLRSplit_;
241  torque_split_per_wheel[WHEEL_FR] = 1. - FrontLRSplit_;
242  torque_split_per_wheel[WHEEL_RL] = 0.0;
243  torque_split_per_wheel[WHEEL_RR] = 0.0;
244  }
245  break;
246  case DIFF_OPEN_REAR:
247  {
248  torque_split_per_wheel[WHEEL_FL] = 0.0;
249  torque_split_per_wheel[WHEEL_FR] = 0.0;
250  torque_split_per_wheel[WHEEL_RL] = RearLRSplit_;
251  torque_split_per_wheel[WHEEL_RR] = 1. - RearLRSplit_;
252  }
253  break;
254  case DIFF_OPEN_4WD:
255  {
256  const double front = FrontRearSplit_;
257  const double rear = 1. - FrontRearSplit_;
258 
259  torque_split_per_wheel[WHEEL_FL] = front * FrontLRSplit_;
260  torque_split_per_wheel[WHEEL_FR] = front * (1. - FrontLRSplit_);
261  torque_split_per_wheel[WHEEL_RL] = rear * RearLRSplit_;
262  torque_split_per_wheel[WHEEL_RR] = rear * (1. - RearLRSplit_);
263  }
264  break;
265  case DIFF_TORSEN_FRONT:
266  {
267  // no torque to rear
268  torque_split_per_wheel[WHEEL_RL] = 0.0;
269  torque_split_per_wheel[WHEEL_RR] = 0.0;
270 
273  FrontLRSplit_, torque_split_per_wheel[WHEEL_FL],
274  torque_split_per_wheel[WHEEL_FR]);
275  }
276  break;
277  case DIFF_TORSEN_REAR:
278  {
279  // no torque to front
280  torque_split_per_wheel[WHEEL_FL] = 0.0;
281  torque_split_per_wheel[WHEEL_FR] = 0.0;
282 
285  RearLRSplit_, torque_split_per_wheel[WHEEL_RL],
286  torque_split_per_wheel[WHEEL_RR]);
287  }
288  break;
289  case DIFF_TORSEN_4WD:
290  {
291  // here we have magic
292  const double w_FL = wheels_info_[WHEEL_FL].getW();
293  const double w_FR = wheels_info_[WHEEL_FR].getW();
294  const double w_RL = wheels_info_[WHEEL_RL].getW();
295  const double w_RR = wheels_info_[WHEEL_RR].getW();
296  const double w_F = w_FL + w_FR;
297  const double w_R = w_RL + w_RR;
298 
299  double t_F = 0.0;
300  double t_R = 0.0;
301  // front-rear
303 
304  double t_FL = 0.0;
305  double t_FR = 0.0;
306  // front left-right
307  computeDiffTorqueSplit(w_FL, w_FR, FrontLRBias_, FrontLRSplit_, t_FL, t_FR);
308 
309  double t_RL = 0.0;
310  double t_RR = 0.0;
311  // rear left-right
312  computeDiffTorqueSplit(w_RL, w_RR, RearLRBias_, RearLRSplit_, t_RL, t_RR);
313 
314  torque_split_per_wheel[WHEEL_FL] = t_F * t_FL;
315  torque_split_per_wheel[WHEEL_FR] = t_F * t_FR;
316  torque_split_per_wheel[WHEEL_RL] = t_R * t_RL;
317  torque_split_per_wheel[WHEEL_RR] = t_R * t_RR;
318  }
319  break;
320  default:
321  {
322  // fatal - unknown diff!
323  ASSERTMSG_(
324  0,
325  "DynamicsAckermannDrivetrain::invoke_motor_controllers: \
326  Unknown differential type!");
327  }
328  break;
329  }
330 
331  ASSERT_(out_torque_per_wheel.size() == 4);
332  for (int i = 0; i < 4; i++)
333  {
334  out_torque_per_wheel[i] = co.drive_torque * torque_split_per_wheel[i];
335  }
336 
337  // Kinematically-driven steering wheels:
338  // Ackermann formulas for inner&outer weels turning angles wrt the
339  // equivalent (central) one:
342  }
343  return out_torque_per_wheel;
344 }
345 
347  const double desired_equiv_steer_ang, double& out_fl_ang, double& out_fr_ang) const
348 {
349  // EQ1: cot(d)+0.5*w/l = cot(do)
350  // EQ2: cot(di)=cot(do)-w/l
351  const double w = wheels_info_[WHEEL_FL].y - wheels_info_[WHEEL_FR].y;
352  const double l = wheels_info_[WHEEL_FL].x - wheels_info_[WHEEL_RL].x;
353  ASSERT_(l > 0);
354  const double w_l = w / l;
355  const double delta = b2Clamp(std::abs(desired_equiv_steer_ang), 0.0, max_steer_ang_);
356 
357  const bool delta_neg = (desired_equiv_steer_ang < 0);
358  ASSERT_LT_(delta, 0.5 * M_PI - 0.01);
359  const double cot_do = 1.0 / tan(delta) + 0.5 * w_l;
360  const double cot_di = cot_do - w_l;
361  // delta>0: do->right, di->left wheel
362  // delta<0: do->left , di->right wheel
363  (delta_neg ? out_fr_ang : out_fl_ang) = atan(1.0 / cot_di) * (delta_neg ? -1.0 : 1.0);
364  (delta_neg ? out_fl_ang : out_fr_ang) = atan(1.0 / cot_do) * (delta_neg ? -1.0 : 1.0);
365 }
366 
368  const double w1, const double w2, const double diffBias, const double splitRatio, double& t1,
369  double& t2)
370 {
371  if (mrpt::signWithZero(w1) == 0.0 || mrpt::signWithZero(w2) == 0.0)
372  {
373  t1 = splitRatio;
374  t2 = 1.0 - splitRatio;
375  return;
376  }
377 
378  const double w1Abs = std::abs(w1);
379  const double w2Abs = std::abs(w2);
380  const double omegaMax = std::max(w1Abs, w2Abs);
381  const double omegaMin = std::min(w1Abs, w2Abs);
382 
383  const double delta = omegaMax - diffBias * omegaMin;
384 
385  const double deltaTorque = (delta > 0) ? delta / omegaMax : 0.0f;
386  const double f1 =
387  (w1Abs - w2Abs > 0) ? splitRatio * (1.0f - deltaTorque) : splitRatio * (1.0f + deltaTorque);
388  const double f2 = (w1Abs - w2Abs > 0) ? (1.0f - splitRatio) * (1.0f + deltaTorque)
389  : (1.0f - splitRatio) * (1.0f - deltaTorque);
390  const double denom = 1.0f / (f1 + f2);
391 
392  t1 = f1 * denom;
393  t2 = f2 * denom;
394 }
395 
396 // See docs in base class:
398 {
399  mrpt::math::TTwist2D odo_vel;
400  // Equations:
401 
402  // Velocities in local +X at each wheel i={0,1}:
403  // v_i = vx - w_veh * wheel_{i,y} = w_i * R_i
404  // Re-arranging:
405  const double w0 = wheels_info_[WHEEL_RL].getW();
406  const double w1 = wheels_info_[WHEEL_RR].getW();
407  const double R0 = wheels_info_[WHEEL_RL].diameter * 0.5;
408  const double R1 = wheels_info_[WHEEL_RR].diameter * 0.5;
409 
410  const double Ay = wheels_info_[WHEEL_RL].y - wheels_info_[WHEEL_RR].y;
411  ASSERTMSG_(
412  Ay != 0.0,
413  "The two wheels of a differential vehicle cannot be at the same Y "
414  "coordinate!");
415 
416  const double w_veh = (w1 * R1 - w0 * R0) / Ay;
417  const double vx_veh = w0 * R0 + w_veh * wheels_info_[WHEEL_RL].y;
418 
419  odo_vel.vx = vx_veh;
420  odo_vel.vy = 0.0;
421  odo_vel.omega = w_veh;
422 
423  return odo_vel;
424 }
mvsim::DynamicsAckermannDrivetrain::DifferentialType
DifferentialType
Definition: VehicleAckermann_Drivetrain.h:41
mvsim
Definition: Client.h:21
mvsim::DynamicsAckermannDrivetrain::getVelocityLocalOdoEstimate
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const override
Definition: VehicleAckermann_Drivetrain.cpp:397
mvsim::VisualObject::world_
World * world_
Definition: VisualObject.h:73
mvsim::DynamicsAckermannDrivetrain::WHEEL_FR
@ WHEEL_FR
Definition: VehicleAckermann_Drivetrain.h:38
mvsim::DynamicsAckermannDrivetrain::DIFF_TORSEN_4WD
@ DIFF_TORSEN_4WD
Definition: VehicleAckermann_Drivetrain.h:49
mvsim::VehicleBase::chassis_z_max_
double chassis_z_max_
Definition: VehicleBase.h:187
mvsim::VehicleBase::fixture_wheels_
std::vector< b2Fixture * > fixture_wheels_
Definition: VehicleBase.h:208
mvsim::TParamEntry
Definition: TParameterDefinitions.h:38
mvsim::VehicleBase::chassis_mass_
double chassis_mass_
Definition: VehicleBase.h:180
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::DynamicsAckermannDrivetrain::FrontLRSplit_
double FrontLRSplit_
Definition: VehicleAckermann_Drivetrain.h:188
mvsim::VehicleBase::chassis_color_
mrpt::img::TColor chassis_color_
Definition: VehicleBase.h:189
mvsim::DynamicsAckermannDrivetrain::DIFF_TORSEN_FRONT
@ DIFF_TORSEN_FRONT
Definition: VehicleAckermann_Drivetrain.h:47
World.h
mvsim::DynamicsAckermannDrivetrain::computeDiffTorqueSplit
void computeDiffTorqueSplit(const double w1, const double w2, const double diffBias, const double defaultSplitRatio, double &t1, double &t2)
Definition: VehicleAckermann_Drivetrain.cpp:367
mvsim::DynamicsAckermannDrivetrain::max_steer_ang_
double max_steer_ang_
Definition: VehicleAckermann_Drivetrain.h:182
mvsim::DynamicsAckermannDrivetrain::computeFrontWheelAngles
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
Definition: VehicleAckermann_Drivetrain.cpp:346
mrpt
Definition: basic_types.h:36
mvsim::VehicleBase::wheels_info_
std::deque< Wheel > wheels_info_
Definition: VehicleBase.h:201
mvsim::DynamicsAckermannDrivetrain::WHEEL_RR
@ WHEEL_RR
Definition: VehicleAckermann_Drivetrain.h:36
mvsim::DynamicsAckermannDrivetrain::TControllerOutput::drive_torque
double drive_torque
Definition: VehicleAckermann_Drivetrain.h:68
xml_utils.h
f
f
rapidxml::xml_attribute< char >
VehicleAckermann_Drivetrain.h
b2Clamp
T b2Clamp(T a, T low, T high)
Definition: b2_math.h:648
mvsim::DynamicsAckermannDrivetrain::diff_type_
DifferentialType diff_type_
min turning radius
Definition: VehicleAckermann_Drivetrain.h:185
mvsim::DynamicsAckermannDrivetrain::TControllerOutput
Definition: VehicleAckermann_Drivetrain.h:66
mvsim::TSimulContext
Definition: basic_types.h:58
rapidxml::xml_node::first_node
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:936
mvsim::TParameterDefinitions
std::map< std::string, TParamEntry > TParameterDefinitions
Definition: TParameterDefinitions.h:64
mvsim::DynamicsAckermannDrivetrain::FrontRearSplit_
double FrontRearSplit_
Definition: VehicleAckermann_Drivetrain.h:187
mvsim::DynamicsAckermannDrivetrain::FrontLRBias_
double FrontLRBias_
Definition: VehicleAckermann_Drivetrain.h:192
mvsim::DynamicsAckermannDrivetrain::DIFF_TORSEN_REAR
@ DIFF_TORSEN_REAR
Definition: VehicleAckermann_Drivetrain.h:48
mvsim::DynamicsAckermannDrivetrain::DIFF_OPEN_FRONT
@ DIFF_OPEN_FRONT
Definition: VehicleAckermann_Drivetrain.h:43
mvsim::DynamicsAckermannDrivetrain::TControllerInput::context
TSimulContext context
Definition: VehicleAckermann_Drivetrain.h:64
mvsim::DynamicsAckermannDrivetrain::TControllerInput
Definition: VehicleAckermann_Drivetrain.h:62
mvsim::DynamicsAckermannDrivetrain::invoke_motor_controllers
virtual std::vector< double > invoke_motor_controllers(const TSimulContext &context) override
Definition: VehicleAckermann_Drivetrain.cpp:219
mvsim::DynamicsAckermannDrivetrain::WHEEL_RL
@ WHEEL_RL
Definition: VehicleAckermann_Drivetrain.h:35
mvsim::DynamicsAckermannDrivetrain::RearLRSplit_
double RearLRSplit_
Definition: VehicleAckermann_Drivetrain.h:189
mvsim::DynamicsAckermannDrivetrain::controller_
ControllerBase::Ptr controller_
The installed controller.
Definition: VehicleAckermann_Drivetrain.h:180
mvsim::DynamicsAckermannDrivetrain::DIFF_OPEN_REAR
@ DIFF_OPEN_REAR
Definition: VehicleAckermann_Drivetrain.h:44
mvsim::World
Definition: World.h:82
mvsim::DynamicsAckermannDrivetrain::FrontRearBias_
double FrontRearBias_
Definition: VehicleAckermann_Drivetrain.h:191
mvsim::VehicleBase
Definition: VehicleBase.h:44
rapidxml::xml_node< char >
mvsim::DynamicsAckermannDrivetrain::DIFF_OPEN_4WD
@ DIFF_OPEN_4WD
Definition: VehicleAckermann_Drivetrain.h:45
std
mvsim::DynamicsAckermannDrivetrain::TControllerOutput::steer_ang
double steer_ang
Equivalent Ackermann steering angle.
Definition: VehicleAckermann_Drivetrain.h:69
mvsim::VehicleBase::chassis_poly_
mrpt::math::TPolygon2D chassis_poly_
Definition: VehicleBase.h:181
mvsim::DynamicsAckermannDrivetrain::RearLRBias_
double RearLRBias_
Definition: VehicleAckermann_Drivetrain.h:193
mvsim::parse_xmlnode_shape
void parse_xmlnode_shape(const rapidxml::xml_node< char > &xml_node, mrpt::math::TPolygon2D &out_poly, const char *functionNameContext="")
Definition: xml_utils.cpp:258
mvsim::DynamicsAckermannDrivetrain::WHEEL_FL
@ WHEEL_FL
Definition: VehicleAckermann_Drivetrain.h:37
mrpt::math
Definition: xml_utils.h:22
mvsim::VehicleBase::fixture_chassis_
b2Fixture * fixture_chassis_
Created at.
Definition: VehicleBase.h:204
mvsim::DynamicsAckermannDrivetrain::DynamicsAckermannDrivetrain
DynamicsAckermannDrivetrain(World *parent)
Definition: VehicleAckermann_Drivetrain.cpp:23
rapidxml.hpp
mvsim::parse_xmlnode_attribs
void parse_xmlnode_attribs(const rapidxml::xml_node< char > &xml_node, const TParameterDefinitions &params, const std::map< std::string, std::string > &variableNamesValues={}, const char *functionNameContext="")
Definition: xml_utils.cpp:182
rapidxml::xml_node::first_attribute
xml_attribute< Ch > * first_attribute(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:1025
mvsim::VehicleBase::chassis_z_min_
double chassis_z_min_
Definition: VehicleBase.h:187
mvsim::DynamicsAckermannDrivetrain::dynamics_load_params_from_xml
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node) override
Definition: VehicleAckermann_Drivetrain.cpp:72
mvsim::VehicleBase::updateMaxRadiusFromPoly
void updateMaxRadiusFromPoly()
Definition: VehicleBase.cpp:577


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