VehicleAckermann.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 
11 #include <mvsim/World.h>
12 
13 #include "xml_utils.h"
14 
15 #include <mrpt/opengl/COpenGLScene.h>
16 #include <rapidxml.hpp>
17 #include <cmath>
18 
19 using namespace mvsim;
20 using namespace std;
21 
22 // Ctor:
24  : VehicleBase(parent, 4 /*num wheels*/),
25  m_max_steer_ang(DEG2RAD(30))
26 {
27  using namespace mrpt::math;
28 
29  m_chassis_mass = 500.0;
30  m_chassis_z_min = 0.20;
31  m_chassis_z_max = 1.40;
32  m_chassis_color = TColor(0xe8, 0x30, 0x00);
33 
34  // Default shape:
35  m_chassis_poly.clear();
36  m_chassis_poly.push_back(TPoint2D(-0.8, -1.0));
37  m_chassis_poly.push_back(TPoint2D(-0.8, 1.0));
38  m_chassis_poly.push_back(TPoint2D(1.5, 0.9));
39  m_chassis_poly.push_back(TPoint2D(1.8, 0.8));
40  m_chassis_poly.push_back(TPoint2D(1.8, -0.8));
41  m_chassis_poly.push_back(TPoint2D(1.5, -0.9));
42  updateMaxRadiusFromPoly();
43 
44  m_fixture_chassis = NULL;
45  for (int i = 0; i < 4; i++) m_fixture_wheels[i] = NULL;
46 
47  // Default values:
48  // rear-left:
49  m_wheels_info[WHEEL_RL].x = 0;
50  m_wheels_info[WHEEL_RL].y = 0.9;
51  // rear-right:
52  m_wheels_info[WHEEL_RR].x = 0;
53  m_wheels_info[WHEEL_RR].y = -0.9;
54  // Front-left:
55  m_wheels_info[WHEEL_FL].x = 1.3;
56  m_wheels_info[WHEEL_FL].y = 0.9;
57  // Front-right:
58  m_wheels_info[WHEEL_FR].x = 1.3;
59  m_wheels_info[WHEEL_FR].y = -0.9;
60 }
61 
64  const rapidxml::xml_node<char>* xml_node)
65 {
66  // <chassis ...> </chassis>
67  const rapidxml::xml_node<char>* xml_chassis =
68  xml_node->first_node("chassis");
69  if (xml_chassis)
70  {
71  // Attribs:
72  std::map<std::string, TParamEntry> attribs;
73  attribs["mass"] = TParamEntry("%lf", &this->m_chassis_mass);
74  attribs["zmin"] = TParamEntry("%lf", &this->m_chassis_z_min);
75  attribs["zmax"] = TParamEntry("%lf", &this->m_chassis_z_max);
76  attribs["color"] = TParamEntry("%color", &this->m_chassis_color);
77 
79  *xml_chassis, attribs,
80  "[DynamicsAckermann::dynamics_load_params_from_xml]");
81 
82  // Shape node (optional, fallback to default shape if none found)
83  const rapidxml::xml_node<char>* xml_shape =
84  xml_chassis->first_node("shape");
85  if (xml_shape)
87  *xml_shape, m_chassis_poly,
88  "[DynamicsAckermann::dynamics_load_params_from_xml]");
89  }
90 
91  //<rl_wheel pos="0 1" mass="6.0" width="0.30" diameter="0.62" />
92  //<rr_wheel pos="0 -1" mass="6.0" width="0.30" diameter="0.62" />
93  //<fl_wheel mass="6.0" width="0.30" diameter="0.62" />
94  //<fr_wheel mass="6.0" width="0.30" diameter="0.62" />
95  const char* w_names[4] = {
96  "rl_wheel", // 0
97  "rr_wheel", // 1
98  "fl_wheel", // 2
99  "fr_wheel" // 3
100  };
101  // Load common params:
102  for (size_t i = 0; i < 4; i++)
103  {
104  const rapidxml::xml_node<char>* xml_wheel =
105  xml_node->first_node(w_names[i]);
106  if (xml_wheel) m_wheels_info[i].loadFromXML(xml_wheel);
107  }
108 
109  //<f_wheels_x>1.3</f_wheels_x>
110  //<f_wheels_d>2.0</f_wheels_d>
111  // Load front ackermann wheels and other params:
112  {
113  double front_x = 1.3;
114  double front_d = 2.0;
115  std::map<std::string, TParamEntry> ack_ps;
116  // Front wheels:
117  ack_ps["f_wheels_x"] = TParamEntry("%lf", &front_x);
118  ack_ps["f_wheels_d"] = TParamEntry("%lf", &front_d);
119  // other params:
120  ack_ps["max_steer_ang_deg"] = TParamEntry("%lf_deg", &m_max_steer_ang);
121 
123  *xml_node, ack_ps,
124  "[DynamicsAckermann::dynamics_load_params_from_xml]");
125 
126  // Front-left:
127  m_wheels_info[WHEEL_FL].x = front_x;
128  m_wheels_info[WHEEL_FL].y = 0.5 * front_d;
129  // Front-right:
130  m_wheels_info[WHEEL_FR].x = front_x;
131  m_wheels_info[WHEEL_FR].y = -0.5 * front_d;
132  }
133 
134  // Vehicle controller:
135  // -------------------------------------------------
136  {
137  const rapidxml::xml_node<char>* xml_control =
138  xml_node->first_node("controller");
139  if (xml_control)
140  {
141  rapidxml::xml_attribute<char>* control_class =
142  xml_control->first_attribute("class");
143  if (!control_class || !control_class->value())
144  throw runtime_error(
145  "[DynamicsAckermann] Missing 'class' attribute in "
146  "<controller> XML node");
147 
148  const std::string sCtrlClass = std::string(control_class->value());
149  if (sCtrlClass == ControllerRawForces::class_name())
150  m_controller =
152  else if (sCtrlClass == ControllerTwistFrontSteerPID::class_name())
153  m_controller =
155  else if (sCtrlClass == ControllerFrontSteerPID::class_name())
156  m_controller =
158  else
159  throw runtime_error(
160  mrpt::format(
161  "[DynamicsAckermann] Unknown 'class'='%s' in "
162  "<controller> XML node",
163  sCtrlClass.c_str()));
164 
165  m_controller->load_config(*xml_control);
166  }
167  }
168  // Default controller:
169  if (!m_controller)
171 }
172 
173 // See docs in base class:
175  const TSimulContext& context, std::vector<double>& out_torque_per_wheel)
176 {
177  // Longitudinal forces at each wheel:
178  out_torque_per_wheel.assign(4, 0.0);
179 
180  if (m_controller)
181  {
182  // Invoke controller:
183  TControllerInput ci;
184  ci.context = context;
186  m_controller->control_step(ci, co);
187  // Take its output:
188  out_torque_per_wheel[WHEEL_RL] = co.rl_torque;
189  out_torque_per_wheel[WHEEL_RR] = co.rr_torque;
190  out_torque_per_wheel[WHEEL_FL] = co.fl_torque;
191  out_torque_per_wheel[WHEEL_FR] = co.fr_torque;
192 
193  // Kinematically-driven steering wheels:
194  // Ackermann formulas for inner&outer weels turning angles wrt the
195  // equivalent (central) one:
197  co.steer_ang, m_wheels_info[WHEEL_FL].yaw,
198  m_wheels_info[WHEEL_FR].yaw);
199  }
200 }
201 
203  const double desired_equiv_steer_ang, double& out_fl_ang,
204  double& out_fr_ang) const
205 {
206  // EQ1: cot(d)+0.5*w/l = cot(do)
207  // EQ2: cot(di)=cot(do)-w/l
208  const double w = m_wheels_info[WHEEL_FL].y - m_wheels_info[WHEEL_FR].y;
209  const double l = m_wheels_info[WHEEL_FL].x - m_wheels_info[WHEEL_RL].x;
210  ASSERT_(l > 0);
211  const double w_l = w / l;
212  const double delta =
213  b2Clamp(std::abs(desired_equiv_steer_ang), 0.0, m_max_steer_ang);
214 
215  const bool delta_neg = (desired_equiv_steer_ang < 0);
216  ASSERT_BELOW_(delta, 0.5 * M_PI - 0.01);
217  const double cot_do = 1.0 / tan(delta) + 0.5 * w_l;
218  const double cot_di = cot_do - w_l;
219  // delta>0: do->right, di->left wheel
220  // delta<0: do->left , di->right wheel
221  (delta_neg ? out_fr_ang : out_fl_ang) =
222  atan(1.0 / cot_di) * (delta_neg ? -1.0 : 1.0);
223  (delta_neg ? out_fl_ang : out_fr_ang) =
224  atan(1.0 / cot_do) * (delta_neg ? -1.0 : 1.0);
225 }
226 
227 // See docs in base class:
229 {
230  vec3 odo_vel;
231  // Equations:
232 
233  // Velocities in local +X at each wheel i={0,1}:
234  // v_i = vx - w_veh * wheel_{i,y} = w_i * R_i
235  // Re-arranging:
236  const double w0 = m_wheels_info[WHEEL_RL].getW();
237  const double w1 = m_wheels_info[WHEEL_RR].getW();
238  const double R0 = m_wheels_info[WHEEL_RL].diameter * 0.5;
239  const double R1 = m_wheels_info[WHEEL_RR].diameter * 0.5;
240 
241  const double Ay = m_wheels_info[WHEEL_RL].y - m_wheels_info[WHEEL_RR].y;
242  ASSERTMSG_(
243  Ay != 0.0,
244  "The two wheels of a differential vehicle CAN'T by at the same Y "
245  "coordinate!");
246 
247  const double w_veh = (w1 * R1 - w0 * R0) / Ay;
248  const double vx_veh = w0 * R0 + w_veh * m_wheels_info[WHEEL_RL].y;
249 
250  odo_vel.vals[0] = vx_veh;
251  odo_vel.vals[2] = w_veh;
252 
253  // v_y = 0
254  odo_vel.vals[1] = 0.0;
255 
256 #if 0 // Debug
257  {
258  vec3 gt_vel = this->getVelocityLocal();
259  printf("\n gt: vx=%7.03f, vy=%7.03f, w= %7.03fdeg\n", gt_vel.vals[0], gt_vel.vals[1], mrpt::utils::RAD2DEG(gt_vel.vals[2]));
260  printf("odo: vx=%7.03f, vy=%7.03f, w= %7.03fdeg\n", odo_vel.vals[0], odo_vel.vals[1], mrpt::utils::RAD2DEG(odo_vel.vals[2]));
261  }
262 #endif
263  return odo_vel;
264 }
This file contains rapidxml parser and DOM implementation.
void parse_xmlnode_shape(const rapidxml::xml_node< char > &xml_node, mrpt::math::TPolygon2D &out_poly, const char *function_name_context="")
Definition: xml_utils.cpp:239
Ch * value() const
Definition: rapidxml.hpp:692
DynamicsAckermann(World *parent)
ControllerBasePtr m_controller
The installed controller.
double vals[3]
Definition: basic_types.h:64
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:936
void parse_xmlnode_attribs(const rapidxml::xml_node< char > &xml_node, const std::map< std::string, TParamEntry > &params, const char *function_name_context="")
Definition: xml_utils.cpp:160
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const std::map< std::string, TParamEntry > &params, const char *function_name_context="")
Definition: xml_utils.cpp:196
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)
virtual vec3 getVelocityLocalOdoEstimate() const
xml_attribute< Ch > * first_attribute(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:1025
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
TFSIMD_FORCE_INLINE const tfScalar & w() const
std::shared_ptr< ControllerBase > ControllerBasePtr
T b2Clamp(T a, T low, T high)
Definition: b2Math.h:654
double steer_ang
Equivalent ackerman steering angle.
vec3 getVelocityLocal() const
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel)


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