VehicleAckermann_Drivetrain.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2020 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 
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*/), m_max_steer_ang(mrpt::DEG2RAD(30))
25 {
26  using namespace mrpt::math;
27 
28  m_chassis_mass = 500.0;
29  m_chassis_z_min = 0.20;
30  m_chassis_z_max = 1.40;
31  m_chassis_color = mrpt::img::TColor(0xe8, 0x30, 0x00);
32 
33  // Default shape:
34  m_chassis_poly.clear();
35  m_chassis_poly.emplace_back(-0.8, -1.0);
36  m_chassis_poly.emplace_back(-0.8, 1.0);
37  m_chassis_poly.emplace_back(1.5, 0.9);
38  m_chassis_poly.emplace_back(1.8, 0.8);
39  m_chassis_poly.emplace_back(1.8, -0.8);
40  m_chassis_poly.emplace_back(1.5, -0.9);
42 
43  m_fixture_chassis = nullptr;
44  for (int i = 0; i < 4; i++) m_fixture_wheels[i] = nullptr;
45 
46  // Default values:
47  // rear-left:
48  m_wheels_info[WHEEL_RL].x = 0;
49  m_wheels_info[WHEEL_RL].y = 0.9;
50  // rear-right:
51  m_wheels_info[WHEEL_RR].x = 0;
52  m_wheels_info[WHEEL_RR].y = -0.9;
53  // Front-left:
54  m_wheels_info[WHEEL_FL].x = 1.3;
55  m_wheels_info[WHEEL_FL].y = 0.9;
56  // Front-right:
57  m_wheels_info[WHEEL_FR].x = 1.3;
58  m_wheels_info[WHEEL_FR].y = -0.9;
59 
60  m_FrontRearSplit = 0.5;
61  m_FrontLRSplit = 0.5;
62  m_RearLRSplit = 0.5;
63 
64  m_FrontRearBias = 1.5;
65  m_FrontLRBias = 1.5;
66  m_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 =
77  xml_node->first_node("chassis");
78  if (xml_chassis)
79  {
80  // Attribs:
82  attribs["mass"] = TParamEntry("%lf", &this->m_chassis_mass);
83  attribs["zmin"] = TParamEntry("%lf", &this->m_chassis_z_min);
84  attribs["zmax"] = TParamEntry("%lf", &this->m_chassis_z_max);
85  attribs["color"] = TParamEntry("%color", &this->m_chassis_color);
86 
88  *xml_chassis, attribs, {},
89  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
90 
91  // Shape node (optional, fallback to default shape if none found)
92  const rapidxml::xml_node<char>* xml_shape =
93  xml_chassis->first_node("shape");
94  if (xml_shape)
96  *xml_shape, m_chassis_poly,
97  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
98  }
99 
100  //<rl_wheel pos="0 1" mass="6.0" width="0.30" diameter="0.62" />
101  //<rr_wheel pos="0 -1" mass="6.0" width="0.30" diameter="0.62" />
102  //<fl_wheel mass="6.0" width="0.30" diameter="0.62" />
103  //<fr_wheel mass="6.0" width="0.30" diameter="0.62" />
104  const char* w_names[4] = {
105  "rl_wheel", // 0
106  "rr_wheel", // 1
107  "fl_wheel", // 2
108  "fr_wheel" // 3
109  };
110  // Load common params:
111  for (size_t i = 0; i < 4; i++)
112  {
113  const rapidxml::xml_node<char>* xml_wheel =
114  xml_node->first_node(w_names[i]);
115  if (xml_wheel) m_wheels_info[i].loadFromXML(xml_wheel);
116  }
117 
118  //<f_wheels_x>1.3</f_wheels_x>
119  //<f_wheels_d>2.0</f_wheels_d>
120  // Load front ackermann wheels and other params:
121  {
122  double front_x = 1.3;
123  double front_d = 2.0;
124  TParameterDefinitions ack_ps;
125  // Front wheels:
126  ack_ps["f_wheels_x"] = TParamEntry("%lf", &front_x);
127  ack_ps["f_wheels_d"] = TParamEntry("%lf", &front_d);
128  // other params:
129  ack_ps["max_steer_ang_deg"] = TParamEntry("%lf_deg", &m_max_steer_ang);
130 
132  *xml_node, ack_ps, {},
133  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
134 
135  // Front-left:
136  m_wheels_info[WHEEL_FL].x = front_x;
137  m_wheels_info[WHEEL_FL].y = 0.5 * front_d;
138  // Front-right:
139  m_wheels_info[WHEEL_FR].x = front_x;
140  m_wheels_info[WHEEL_FR].y = -0.5 * front_d;
141  }
142 
143  // Drivetrain parameters
144  // Watch the order of DifferentialType enum!
145  const char* drive_names[6] = {"open_front", "open_rear", "open_4wd",
146  "torsen_front", "torsen_rear", "torsen_4wd"};
147 
148  const rapidxml::xml_node<char>* xml_drive =
149  xml_node->first_node("drivetrain");
150  if (xml_drive)
151  {
153  std::string diff_type;
154  attribs["type"] = TParamEntry("%s", &diff_type);
155 
157  *xml_drive, attribs, {},
158  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
159 
160  for (size_t i = 0; i < DifferentialType::DIFF_MAX; ++i)
161  {
162  if (diff_type == drive_names[i])
163  {
165  break;
166  }
167  }
168 
169  TParameterDefinitions drive_params;
170  drive_params["front_rear_split"] =
171  TParamEntry("%lf", &m_FrontRearSplit);
172  drive_params["front_rear_bias"] = TParamEntry("%lf", &m_FrontRearBias);
173  drive_params["front_left_right_split"] =
174  TParamEntry("%lf", &m_FrontLRSplit);
175  drive_params["front_left_right_bias"] =
176  TParamEntry("%lf", &m_FrontLRBias);
177  drive_params["rear_left_right_split"] =
178  TParamEntry("%lf", &m_RearLRSplit);
179  drive_params["rear_left_right_bias"] =
180  TParamEntry("%lf", &m_RearLRBias);
181 
183  *xml_drive, drive_params, {},
184  "[DynamicsAckermannDrivetrain::dynamics_load_params_from_xml]");
185  }
186 
187  // Vehicle controller:
188  // -------------------------------------------------
189  {
190  const rapidxml::xml_node<char>* xml_control =
191  xml_node->first_node("controller");
192  if (xml_control)
193  {
194  rapidxml::xml_attribute<char>* control_class =
195  xml_control->first_attribute("class");
196  if (!control_class || !control_class->value())
197  throw runtime_error(
198  "[DynamicsAckermannDrivetrain] Missing 'class' attribute "
199  "in <controller> XML node");
200 
201  const std::string sCtrlClass = std::string(control_class->value());
202  if (sCtrlClass == ControllerRawForces::class_name())
203  m_controller =
205  else if (sCtrlClass == ControllerTwistFrontSteerPID::class_name())
206  m_controller =
208  else if (sCtrlClass == ControllerFrontSteerPID::class_name())
209  m_controller =
211  else
212  throw runtime_error(mrpt::format(
213  "[DynamicsAckermannDrivetrain] Unknown 'class'='%s' in "
214  "<controller> XML node",
215  sCtrlClass.c_str()));
216 
217  m_controller->load_config(*xml_control);
218  }
219  }
220  // Default controller:
221  if (!m_controller)
223 }
224 
225 // See docs in base class:
227  const TSimulContext& context, std::vector<double>& out_torque_per_wheel)
228 {
229  // Longitudinal forces at each wheel:
230  out_torque_per_wheel.assign(4, 0.0);
231  double torque_split_per_wheel[4] = {0.0};
232 
233  if (m_controller)
234  {
235  // Invoke controller:
236  TControllerInput ci;
237  ci.context = context;
239  m_controller->control_step(ci, co);
240  // Take its output:
241 
242  switch (m_diff_type)
243  {
244  case DIFF_OPEN_FRONT:
245  {
246  torque_split_per_wheel[WHEEL_FL] = m_FrontLRSplit;
247  torque_split_per_wheel[WHEEL_FR] = 1. - m_FrontLRSplit;
248  torque_split_per_wheel[WHEEL_RL] = 0.0;
249  torque_split_per_wheel[WHEEL_RR] = 0.0;
250  }
251  break;
252  case DIFF_OPEN_REAR:
253  {
254  torque_split_per_wheel[WHEEL_FL] = 0.0;
255  torque_split_per_wheel[WHEEL_FR] = 0.0;
256  torque_split_per_wheel[WHEEL_RL] = m_RearLRSplit;
257  torque_split_per_wheel[WHEEL_RR] = 1. - m_RearLRSplit;
258  }
259  break;
260  case DIFF_OPEN_4WD:
261  {
262  const double front = m_FrontRearSplit;
263  const double rear = 1. - m_FrontRearSplit;
264 
265  torque_split_per_wheel[WHEEL_FL] = front * m_FrontLRSplit;
266  torque_split_per_wheel[WHEEL_FR] =
267  front * (1. - m_FrontLRSplit);
268  torque_split_per_wheel[WHEEL_RL] = rear * m_RearLRSplit;
269  torque_split_per_wheel[WHEEL_RR] = rear * (1. - m_RearLRSplit);
270  }
271  break;
272  case DIFF_TORSEN_FRONT:
273  {
274  // no torque to rear
275  torque_split_per_wheel[WHEEL_RL] = 0.0;
276  torque_split_per_wheel[WHEEL_RR] = 0.0;
277 
279  m_wheels_info[WHEEL_FL].getW(),
281  m_FrontLRSplit, torque_split_per_wheel[WHEEL_FL],
282  torque_split_per_wheel[WHEEL_FR]);
283  }
284  break;
285  case DIFF_TORSEN_REAR:
286  {
287  // no torque to front
288  torque_split_per_wheel[WHEEL_FL] = 0.0;
289  torque_split_per_wheel[WHEEL_FR] = 0.0;
290 
292  m_wheels_info[WHEEL_RL].getW(),
294  torque_split_per_wheel[WHEEL_RL],
295  torque_split_per_wheel[WHEEL_RR]);
296  }
297  break;
298  case DIFF_TORSEN_4WD:
299  {
300  // here we have magic
301  const double w_FL = m_wheels_info[WHEEL_FL].getW();
302  const double w_FR = m_wheels_info[WHEEL_FR].getW();
303  const double w_RL = m_wheels_info[WHEEL_RL].getW();
304  const double w_RR = m_wheels_info[WHEEL_RR].getW();
305  const double w_F = w_FL + w_FR;
306  const double w_R = w_RL + w_RR;
307 
308  double t_F = 0.0;
309  double t_R = 0.0;
310  // front-rear
312  w_F, w_R, m_FrontRearBias, m_FrontRearSplit, t_F, t_R);
313 
314  double t_FL = 0.0;
315  double t_FR = 0.0;
316  // front left-right
318  w_FL, w_FR, m_FrontLRBias, m_FrontLRSplit, t_FL, t_FR);
319 
320  double t_RL = 0.0;
321  double t_RR = 0.0;
322  // rear left-right
324  w_RL, w_RR, m_RearLRBias, m_RearLRSplit, t_RL, t_RR);
325 
326  torque_split_per_wheel[WHEEL_FL] = t_F * t_FL;
327  torque_split_per_wheel[WHEEL_FR] = t_F * t_FR;
328  torque_split_per_wheel[WHEEL_RL] = t_R * t_RL;
329  torque_split_per_wheel[WHEEL_RR] = t_R * t_RR;
330  }
331  break;
332  default:
333  {
334  // fatal - unknown diff!
335  ASSERTMSG_(
336  0,
337  "DynamicsAckermannDrivetrain::invoke_motor_controllers: \
338  Unknown differential type!");
339  }
340  break;
341  }
342 
343  ASSERT_(out_torque_per_wheel.size() == 4);
344  for (int i = 0; i < 4; i++)
345  {
346  out_torque_per_wheel[i] =
347  co.drive_torque * torque_split_per_wheel[i];
348  }
349 
350  // Kinematically-driven steering wheels:
351  // Ackermann formulas for inner&outer weels turning angles wrt the
352  // equivalent (central) one:
355  m_wheels_info[WHEEL_FR].yaw);
356  }
357 }
358 
360  const double desired_equiv_steer_ang, double& out_fl_ang,
361  double& out_fr_ang) const
362 {
363  // EQ1: cot(d)+0.5*w/l = cot(do)
364  // EQ2: cot(di)=cot(do)-w/l
365  const double w = m_wheels_info[WHEEL_FL].y - m_wheels_info[WHEEL_FR].y;
366  const double l = m_wheels_info[WHEEL_FL].x - m_wheels_info[WHEEL_RL].x;
367  ASSERT_(l > 0);
368  const double w_l = w / l;
369  const double delta =
370  b2Clamp(std::abs(desired_equiv_steer_ang), 0.0, m_max_steer_ang);
371 
372  const bool delta_neg = (desired_equiv_steer_ang < 0);
373  ASSERT_LT_(delta, 0.5 * M_PI - 0.01);
374  const double cot_do = 1.0 / tan(delta) + 0.5 * w_l;
375  const double cot_di = cot_do - w_l;
376  // delta>0: do->right, di->left wheel
377  // delta<0: do->left , di->right wheel
378  (delta_neg ? out_fr_ang : out_fl_ang) =
379  atan(1.0 / cot_di) * (delta_neg ? -1.0 : 1.0);
380  (delta_neg ? out_fl_ang : out_fr_ang) =
381  atan(1.0 / cot_do) * (delta_neg ? -1.0 : 1.0);
382 }
383 
385  const double w1, const double w2, const double diffBias,
386  const double splitRatio, double& t1, double& t2)
387 {
388  if (mrpt::signWithZero(w1) == 0.0 || mrpt::signWithZero(w2) == 0.0)
389  {
390  t1 = splitRatio;
391  t2 = 1.0 - splitRatio;
392  return;
393  }
394 
395  const double w1Abs = std::abs(w1);
396  const double w2Abs = std::abs(w2);
397  const double omegaMax = std::max(w1Abs, w2Abs);
398  const double omegaMin = std::min(w1Abs, w2Abs);
399 
400  const double delta = omegaMax - diffBias * omegaMin;
401 
402  const double deltaTorque = (delta > 0) ? delta / omegaMax : 0.0f;
403  const double f1 = (w1Abs - w2Abs > 0) ? splitRatio * (1.0f - deltaTorque)
404  : splitRatio * (1.0f + deltaTorque);
405  const double f2 = (w1Abs - w2Abs > 0)
406  ? (1.0f - splitRatio) * (1.0f + deltaTorque)
407  : (1.0f - splitRatio) * (1.0f - deltaTorque);
408  const double denom = 1.0f / (f1 + f2);
409 
410  t1 = f1 * denom;
411  t2 = f2 * denom;
412 }
413 
414 // See docs in base class:
416  const
417 {
418  mrpt::math::TTwist2D odo_vel;
419  // Equations:
420 
421  // Velocities in local +X at each wheel i={0,1}:
422  // v_i = vx - w_veh * wheel_{i,y} = w_i * R_i
423  // Re-arranging:
424  const double w0 = m_wheels_info[WHEEL_RL].getW();
425  const double w1 = m_wheels_info[WHEEL_RR].getW();
426  const double R0 = m_wheels_info[WHEEL_RL].diameter * 0.5;
427  const double R1 = m_wheels_info[WHEEL_RR].diameter * 0.5;
428 
429  const double Ay = m_wheels_info[WHEEL_RL].y - m_wheels_info[WHEEL_RR].y;
430  ASSERTMSG_(
431  Ay != 0.0,
432  "The two wheels of a differential vehicle CAN'T by at the same Y "
433  "coordinate!");
434 
435  const double w_veh = (w1 * R1 - w0 * R0) / Ay;
436  const double vx_veh = w0 * R0 + w_veh * m_wheels_info[WHEEL_RL].y;
437 
438  odo_vel.vx = vx_veh;
439  odo_vel.vy = 0.0;
440  odo_vel.omega = w_veh;
441 
442  return odo_vel;
443 }
mrpt::img::TColor m_chassis_color
Definition: VehicleBase.h:189
This file contains rapidxml parser and DOM implementation.
void updateMaxRadiusFromPoly()
excludes the mass of wheels)
DifferentialType m_diff_type
min turning radius
std::map< std::string, TParamEntry > TParameterDefinitions
Ch * value() const
Definition: rapidxml.hpp:692
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="")
Definition: xml_utils.cpp:179
GLubyte GLubyte GLubyte GLubyte w
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const override
#define M_PI
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:140
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node) override
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel) override
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:936
GLdouble l
const GLint * attribs
void computeDiffTorqueSplit(const double w1, const double w2, const double diffBias, const double defaultSplitRatio, double &t1, double &t2)
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
double DEG2RAD(const double x)
xml_attribute< Ch > * first_attribute(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:1025
GLdouble GLdouble GLint GLint GLdouble GLdouble GLint GLint GLdouble GLdouble w2
std::vector< Wheel > m_wheels_info
Definition: VehicleBase.h:197
std::shared_ptr< ControllerBase > ControllerBasePtr
double steer_ang
Equivalent ackerman steering angle.
T b2Clamp(T a, T low, T high)
Definition: b2Math.h:653
#define ASSERT_(f)
ControllerBasePtr m_controller
The installed controller.
std::vector< b2Fixture * > m_fixture_wheels
Definition: VehicleBase.h:204
double m_chassis_z_min
each change via updateMaxRadiusFromPoly()
Definition: VehicleBase.h:188
void parse_xmlnode_shape(const rapidxml::xml_node< char > &xml_node, mrpt::math::TPolygon2D &out_poly, const char *functionNameContext="")
Definition: xml_utils.cpp:222
const T1 & f1
mrpt::math::TPolygon2D m_chassis_poly
Definition: VehicleBase.h:185
const T1 const T2 & f2
#define ASSERTMSG_(f, __ERROR_MSG)
b2Fixture * m_fixture_chassis
Created at.
Definition: VehicleBase.h:203
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
const char_t & front(const std::string &s)
GLdouble GLdouble GLint GLint GLdouble GLdouble GLint GLint GLdouble w1
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f


mvsim
Author(s):
autogenerated on Fri May 7 2021 03:05:51