VehicleAckermann.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/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*/)
25 {
26  chassis_mass_ = 500.0;
27  chassis_z_min_ = 0.20;
28  chassis_z_max_ = 1.40;
29  chassis_color_ = mrpt::img::TColor(0xe8, 0x30, 0x00);
30 
31  // Default shape:
32  chassis_poly_.clear();
33  chassis_poly_.emplace_back(-0.8, -1.0);
34  chassis_poly_.emplace_back(-0.8, 1.0);
35  chassis_poly_.emplace_back(1.5, 0.9);
36  chassis_poly_.emplace_back(1.8, 0.8);
37  chassis_poly_.emplace_back(1.8, -0.8);
38  chassis_poly_.emplace_back(1.5, -0.9);
40 
41  fixture_chassis_ = nullptr;
42  for (int i = 0; i < 4; i++) fixture_wheels_[i] = nullptr;
43 
44  // Default values:
45  // rear-left:
46  wheels_info_[WHEEL_RL].x = 0;
47  wheels_info_[WHEEL_RL].y = 0.9;
48  // rear-right:
49  wheels_info_[WHEEL_RR].x = 0;
50  wheels_info_[WHEEL_RR].y = -0.9;
51  // Front-left:
52  wheels_info_[WHEEL_FL].x = 1.3;
53  wheels_info_[WHEEL_FL].y = 0.9;
54  // Front-right:
55  wheels_info_[WHEEL_FR].x = 1.3;
56  wheels_info_[WHEEL_FR].y = -0.9;
57 }
58 
61  const rapidxml::xml_node<char>* xml_node)
62 {
63  const std::map<std::string, std::string> varValues = {{"NAME", name_}};
64 
65  // <chassis ...> </chassis>
66  if (const rapidxml::xml_node<char>* xml_chassis =
67  xml_node->first_node("chassis");
68  xml_chassis)
69  {
70  // Attribs:
71  TParameterDefinitions attribs;
72  attribs["mass"] = TParamEntry("%lf", &this->chassis_mass_);
73  attribs["zmin"] = TParamEntry("%lf", &this->chassis_z_min_);
74  attribs["zmax"] = TParamEntry("%lf", &this->chassis_z_max_);
75  attribs["color"] = TParamEntry("%color", &this->chassis_color_);
76 
78  *xml_chassis, attribs, {},
79  "[DynamicsAckermann::dynamics_load_params_from_xml]");
80 
81  // Shape node (optional, fallback to default shape if none found)
82  if (const rapidxml::xml_node<char>* xml_shape =
83  xml_chassis->first_node("shape");
84  xml_shape)
86  *xml_shape, chassis_poly_,
87  "[DynamicsAckermann::dynamics_load_params_from_xml]");
88  }
89 
90  //<rl_wheel pos="0 1" mass="6.0" width="0.30" diameter="0.62" />
91  //<rr_wheel pos="0 -1" mass="6.0" width="0.30" diameter="0.62" />
92  //<fl_wheel mass="6.0" width="0.30" diameter="0.62" />
93  //<fr_wheel mass="6.0" width="0.30" diameter="0.62" />
94  const char* w_names[4] = {
95  "rl_wheel", // 0
96  "rr_wheel", // 1
97  "fl_wheel", // 2
98  "fr_wheel" // 3
99  };
100  // Load common params:
101  for (size_t i = 0; i < 4; i++)
102  {
103  if (auto xml_wheel = xml_node->first_node(w_names[i]); xml_wheel)
104  {
105  wheels_info_[i].loadFromXML(xml_wheel);
106  }
107  else
108  {
109  world_->logFmt(
110  mrpt::system::LVL_WARN,
111  "No XML entry '%s' found: using defaults for wheel #%u",
112  w_names[i], static_cast<unsigned int>(i));
113  }
114  }
115 
116  //<f_wheels_x>1.3</f_wheels_x>
117  //<f_wheels_d>2.0</f_wheels_d>
118  // Load front ackermann wheels and other params:
119  {
120  double front_x = 1.3;
121  double front_d = 2.0;
122  TParameterDefinitions ack_ps;
123  // Front wheels:
124  ack_ps["f_wheels_x"] = TParamEntry("%lf", &front_x);
125  ack_ps["f_wheels_d"] = TParamEntry("%lf", &front_d);
126  // other params:
127  ack_ps["max_steer_ang_deg"] = TParamEntry("%lf_deg", &max_steer_ang_);
128 
130  *xml_node, ack_ps, varValues,
131  "[DynamicsAckermann::dynamics_load_params_from_xml]");
132 
133  // Front-left:
134  wheels_info_[WHEEL_FL].x = front_x;
135  wheels_info_[WHEEL_FL].y = 0.5 * front_d;
136  // Front-right:
137  wheels_info_[WHEEL_FR].x = front_x;
138  wheels_info_[WHEEL_FR].y = -0.5 * front_d;
139  }
140 
141  // Vehicle controller:
142  // -------------------------------------------------
143  {
144  const rapidxml::xml_node<char>* xml_control =
145  xml_node->first_node("controller");
146  if (xml_control)
147  {
148  rapidxml::xml_attribute<char>* control_class =
149  xml_control->first_attribute("class");
150  if (!control_class || !control_class->value())
151  throw runtime_error(
152  "[DynamicsAckermann] Missing 'class' attribute in "
153  "<controller> XML node");
154 
155  const std::string sCtrlClass = std::string(control_class->value());
156  if (sCtrlClass == ControllerRawForces::class_name())
157  controller_ = std::make_shared<ControllerRawForces>(*this);
158  else if (sCtrlClass == ControllerTwistFrontSteerPID::class_name())
159  controller_ =
160  std::make_shared<ControllerTwistFrontSteerPID>(*this);
161  else if (sCtrlClass == ControllerFrontSteerPID::class_name())
162  controller_ = std::make_shared<ControllerFrontSteerPID>(*this);
163  else
164  THROW_EXCEPTION_FMT(
165  "[DynamicsAckermann] Unknown 'class'='%s' in "
166  "<controller> XML node",
167  sCtrlClass.c_str());
168 
169  controller_->load_config(*xml_control);
170  }
171  }
172  // Default controller:
173  if (!controller_)
174  controller_ = std::make_shared<ControllerRawForces>(*this);
175 }
176 
177 // See docs in base class:
179  const TSimulContext& context)
180 {
181  // Longitudinal forces at each wheel:
182  std::vector<double> out_torque_per_wheel;
183  out_torque_per_wheel.assign(4, 0.0);
184 
185  if (controller_)
186  {
187  // Invoke controller:
188  TControllerInput ci;
189  ci.context = context;
191  controller_->control_step(ci, co);
192  // Take its output:
193  out_torque_per_wheel[WHEEL_RL] = co.rl_torque;
194  out_torque_per_wheel[WHEEL_RR] = co.rr_torque;
195  out_torque_per_wheel[WHEEL_FL] = co.fl_torque;
196  out_torque_per_wheel[WHEEL_FR] = co.fr_torque;
197 
198  // Kinematically-driven steering wheels:
199  // Ackermann formulas for inner&outer weels turning angles wrt the
200  // equivalent (central) one:
203  wheels_info_[WHEEL_FR].yaw);
204  }
205  return out_torque_per_wheel;
206 }
207 
209  const double desired_equiv_steer_ang, double& out_fl_ang,
210  double& out_fr_ang) const
211 {
212  // EQ1: cot(d)+0.5*w/l = cot(do)
213  // EQ2: cot(di)=cot(do)-w/l
214  const double w = wheels_info_[WHEEL_FL].y - wheels_info_[WHEEL_FR].y;
215  const double l = wheels_info_[WHEEL_FL].x - wheels_info_[WHEEL_RL].x;
216  ASSERT_(l > 0);
217  const double w_l = w / l;
218  const double delta =
219  b2Clamp(std::abs(desired_equiv_steer_ang), 0.0, max_steer_ang_);
220 
221  const bool delta_neg = (desired_equiv_steer_ang < 0);
222  ASSERT_LT_(delta, 0.5 * M_PI - 0.01);
223  const double cot_do = 1.0 / tan(delta) + 0.5 * w_l;
224  const double cot_di = cot_do - w_l;
225  // delta>0: do->right, di->left wheel
226  // delta<0: do->left , di->right wheel
227  (delta_neg ? out_fr_ang : out_fl_ang) =
228  atan(1.0 / cot_di) * (delta_neg ? -1.0 : 1.0);
229  (delta_neg ? out_fl_ang : out_fr_ang) =
230  atan(1.0 / cot_do) * (delta_neg ? -1.0 : 1.0);
231 }
232 
233 // See docs in base class:
235 {
236  mrpt::math::TTwist2D odo_vel;
237  // Equations:
238 
239  // Velocities in local +X at each wheel i={0,1}:
240  // v_i = vx - w_veh * wheel_{i,y} = w_i * R_i
241  // Re-arranging:
242  const double w0 = wheels_info_[WHEEL_RL].getW();
243  const double w1 = wheels_info_[WHEEL_RR].getW();
244  const double R0 = wheels_info_[WHEEL_RL].diameter * 0.5;
245  const double R1 = wheels_info_[WHEEL_RR].diameter * 0.5;
246 
247  const double Ay = wheels_info_[WHEEL_RL].y - wheels_info_[WHEEL_RR].y;
248  ASSERTMSG_(
249  Ay != 0.0,
250  "The two wheels of a differential vehicle cannot be at the same Y "
251  "coordinate!");
252 
253  const double w_veh = (w1 * R1 - w0 * R0) / Ay;
254  const double vx_veh = w0 * R0 + w_veh * wheels_info_[WHEEL_RL].y;
255 
256  odo_vel.vx = vx_veh;
257  odo_vel.vy = 0.0;
258  odo_vel.omega = w_veh;
259 
260 #if 0 // Debug
261  {
262  mrpt::math::TTwist2D gt_vel = this->getVelocityLocal();
263  printf("\n gt: vx=%7.03f, vy=%7.03f, w= %7.03fdeg\n", gt_vel.vx, gt_vel.vy, mrpt::RAD2DEG(gt_vel.omega));
264  printf("odo: vx=%7.03f, vy=%7.03f, w= %7.03fdeg\n", odo_vel.vx, odo_vel.vy, mrpt::RAD2DEG(odo_vel.omega));
265  }
266 #endif
267  return odo_vel;
268 }
This file contains rapidxml parser and DOM implementation.
void updateMaxRadiusFromPoly()
std::map< std::string, TParamEntry > TParameterDefinitions
virtual std::vector< double > invoke_motor_controllers(const TSimulContext &context) override
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
DynamicsAckermann(World *parent)
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const override
ControllerBase::Ptr controller_
The installed controller.
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
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:184
#define M_PI
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node) override
std::deque< Wheel > wheels_info_
Definition: VehicleBase.h:209
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:936
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
std::string name_
Definition: Simulable.h:120
mrpt::math::TPolygon2D chassis_poly_
Definition: VehicleBase.h:189
b2Fixture * fixture_chassis_
Created at.
Definition: VehicleBase.h:212
T b2Clamp(T a, T low, T high)
Definition: b2_math.h:648
Ch * value() const
Definition: rapidxml.hpp:692
mrpt::math::TTwist2D getVelocityLocal() const
Definition: Simulable.cpp:116
double steer_ang
Equivalent Ackermann steering angle.
mrpt::img::TColor chassis_color_
Definition: VehicleBase.h:197
void parse_xmlnode_shape(const rapidxml::xml_node< char > &xml_node, mrpt::math::TPolygon2D &out_poly, const char *functionNameContext="")
Definition: xml_utils.cpp:271
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
xml_attribute< Ch > * first_attribute(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:1025
std::vector< b2Fixture * > fixture_wheels_
Definition: VehicleBase.h:216


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