10 #include <mrpt/opengl/COpenGLScene.h>
19 using namespace mvsim;
61 const std::map<std::string, std::string> varValues = {{
"NAME",
name_}};
74 *xml_chassis, attribs, {},
"[DynamicsAckermann::dynamics_load_params_from_xml]");
79 *xml_shape,
chassis_poly_,
"[DynamicsAckermann::dynamics_load_params_from_xml]");
86 const char* w_names[4] = {
93 for (
size_t i = 0; i < 4; i++)
95 if (
auto xml_wheel = xml_node->
first_node(w_names[i]); xml_wheel)
102 mrpt::system::LVL_WARN,
"No XML entry '%s' found: using defaults for wheel #%u",
103 w_names[i],
static_cast<unsigned int>(i));
111 double front_x = 1.3;
112 double front_d = 2.0;
115 ack_ps[
"f_wheels_x"] =
TParamEntry(
"%lf", &front_x);
116 ack_ps[
"f_wheels_d"] =
TParamEntry(
"%lf", &front_d);
121 *xml_node, ack_ps, varValues,
"[DynamicsAckermann::dynamics_load_params_from_xml]");
138 if (!control_class || !control_class->value())
140 "[DynamicsAckermann] Missing 'class' attribute in "
141 "<controller> XML node");
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);
152 "[DynamicsAckermann] Unknown 'class'='%s' in "
153 "<controller> XML node",
167 std::vector<double> out_torque_per_wheel;
168 out_torque_per_wheel.assign(4, 0.0);
189 return out_torque_per_wheel;
193 const double desired_equiv_steer_ang,
double& out_fl_ang,
double& out_fr_ang)
const
200 const double w_l = w / l;
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;
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);
216 mrpt::math::TTwist2D odo_vel;
230 "The two wheels of a differential vehicle cannot be at the same Y "
233 const double w_veh = (w1 * R1 - w0 * R0) / Ay;
238 odo_vel.omega = w_veh;
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));