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


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