VehicleAckermann.h
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 
10 #pragma once
11 
12 #include <mrpt/img/TColor.h>
13 #include <mvsim/PID_Controller.h>
14 #include <mvsim/VehicleBase.h>
15 
16 namespace mvsim
17 {
22 {
24  public:
25  // Wheels: [0]:rear-left, [1]:rear-right, [2]: front-left, [3]: front-right
26  enum
27  {
28  WHEEL_RL = 0,
29  WHEEL_RR = 1,
30  WHEEL_FL = 2,
32  };
33 
34  DynamicsAckermann(World* parent);
35 
37  double getMaxSteeringAngle() const { return m_max_steer_ang; }
38  void setMaxSteeringAngle(double val) { m_max_steer_ang = val; }
43  {
45  };
47  {
48  double fl_torque, fr_torque, rl_torque, rr_torque;
49  double steer_ang;
51  : fl_torque(0),
52  fr_torque(0),
53  rl_torque(0),
54  rr_torque(0),
55  steer_ang(0)
56  {
57  }
58  };
59 
62  typedef std::shared_ptr<ControllerBase> ControllerBasePtr;
63 
64  class ControllerRawForces : public ControllerBase
65  {
66  public:
68  static const char* class_name() { return "raw"; }
71  double setpoint_wheel_torque_l, setpoint_wheel_torque_r,
72  setpoint_steer_ang;
73  virtual void control_step(
76  virtual void load_config(const rapidxml::xml_node<char>& node) override;
77  virtual void teleop_interface(
78  const TeleopInput& in, TeleopOutput& out) override;
79  };
80 
83  class ControllerTwistFrontSteerPID : public ControllerBase
84  {
85  public:
87  static const char* class_name() { return "twist_front_steer_pid"; }
91  setpoint_ang_speed;
92  virtual void control_step(
95  virtual void load_config(const rapidxml::xml_node<char>& node) override;
96  virtual void teleop_interface(
97  const TeleopInput& in, TeleopOutput& out) override;
98 
99  double KP, KI, KD;
100  double max_torque;
101 
102  // See base docs.
103  virtual bool setTwistCommand(const double vx, const double wz) override
104  {
105  setpoint_lin_speed = vx;
106  setpoint_ang_speed = wz;
107  return true;
108  }
109 
110  private:
111  double m_dist_fWheels, m_r2f_L;
112  PID_Controller m_PID[2]; //<! [0]:fl, [1]: fr
113  };
114 
117  class ControllerFrontSteerPID : public ControllerBase
118  {
119  public:
121  static const char* class_name() { return "front_steer_pid"; }
124  double setpoint_lin_speed, setpoint_steer_ang;
125  virtual void control_step(
130  virtual void load_config(const rapidxml::xml_node<char>& node) override;
131  virtual void teleop_interface(
132  const TeleopInput& in, TeleopOutput& out) override;
133 
134  double KP, KI, KD;
135  double max_torque;
136  private:
138  double m_r2f_L;
139  };
140 
141  const ControllerBasePtr& getController() const { return m_controller; }
142  ControllerBasePtr& getController() { return m_controller; }
144  {
145  return m_controller.get();
146  }
147  // end controllers
149 
150  virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const override;
151 
158  const double desired_equiv_steer_ang, double& out_fl_ang,
159  double& out_fr_ang) const;
160 
161  protected:
162  // See base class docs
163  virtual void dynamics_load_params_from_xml(
164  const rapidxml::xml_node<char>* xml_node) override;
165  // See base class doc
166  virtual void invoke_motor_controllers(
167  const TSimulContext& context,
168  std::vector<double>& out_force_per_wheel) override;
169 
170  private:
171  ControllerBasePtr m_controller;
172 
174  double m_max_steer_ang = mrpt::DEG2RAD(30);
175 };
176 } // namespace mvsim
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel) override
DynamicsAckermann(World *parent)
double max_torque
Maximum abs. value torque (for clamp) [Nm].
ControllerBasePtr m_controller
The installed controller.
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const override
const ControllerBasePtr & getController() const
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node) override
GLuint in
void setMaxSteeringAngle(double val)
ControllerBaseTempl< DynamicsAckermann > ControllerBase
virtual bool setTwistCommand(const double vx, const double wz) override
#define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME)
Definition: VehicleBase.h:249
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
ControllerBasePtr & getController()
std::shared_ptr< ControllerBase > ControllerBasePtr
double steer_ang
Equivalent ackerman steering angle.
GLuint GLfloat * val
double getMaxSteeringAngle() const
double max_torque
Maximum abs. value torque (for clamp) [Nm].
virtual ControllerBaseInterface * getControllerInterface() override


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