VehicleAckermann_Drivetrain.h
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 
10 #pragma once
11 
12 #include <mvsim/VehicleBase.h>
13 #include <mvsim/PID_Controller.h>
14 
15 #include <mrpt/opengl/CSetOfObjects.h>
16 #include <mrpt/math/lightweight_geom_data.h>
17 #if MRPT_VERSION<0x199
18 #include <mrpt/utils/TColor.h>
19 using mrpt::utils::TColor;
20 using mrpt::utils::keep_min;
21 using mrpt::utils::keep_max;
22 using mrpt::utils::signWithZero;
23 #else
24 #include <mrpt/img/TColor.h>
25 using mrpt::img::TColor;
26 using mrpt::keep_min;
27 using mrpt::keep_max;
28 using mrpt::signWithZero;
29 #endif
30 
31 namespace mvsim
32 {
42 {
44  public:
45  // Wheels: [0]:rear-left, [1]:rear-right, [2]: front-left, [3]: front-right
46  enum
47  {
48  WHEEL_RL = 0,
49  WHEEL_RR = 1,
50  WHEEL_FL = 2,
52  };
53 
55  {
59 
63 
65  };
66 
68 
70  double getMaxSteeringAngle() const { return m_max_steer_ang; }
71  void setMaxSteeringAngle(double val) { m_max_steer_ang = val; }
76  {
78  };
80  {
81  double drive_torque;
82  double steer_ang;
83  TControllerOutput() : drive_torque(0), steer_ang(0) {}
84  };
85 
89  typedef std::shared_ptr<ControllerBase> ControllerBasePtr;
90 
91  class ControllerRawForces : public ControllerBase
92  {
93  public:
95  static const char* class_name() { return "raw"; }
98  double setpoint_wheel_torque, setpoint_steer_ang;
99  virtual void control_step(
102  co); // See base class docs
103  virtual void load_config(
104  const rapidxml::xml_node<char>& node); // See base class docs
105  virtual void teleop_interface(
106  const TeleopInput& in, TeleopOutput& out); // See base class docs
107  };
108 
111  class ControllerTwistFrontSteerPID : public ControllerBase
112  {
113  public:
115  static const char* class_name() { return "twist_front_steer_pid"; }
119  setpoint_ang_speed;
120  virtual void control_step(
123  virtual void load_config(const rapidxml::xml_node<char>& node);
124  virtual void teleop_interface(const TeleopInput& in, TeleopOutput& out);
125 
126  double KP, KI, KD;
127  double max_torque;
128 
129  // See base docs.
130  virtual bool setTwistCommand(const double vx, const double wz)
131  {
132  setpoint_lin_speed = vx;
133  setpoint_ang_speed = wz;
134  return true;
135  }
136 
137  private:
138  double m_dist_fWheels, m_r2f_L;
140  };
141 
142  class ControllerFrontSteerPID : public ControllerBase
143  {
144  public:
146  static const char* class_name() { return "front_steer_pid"; }
149  double setpoint_lin_speed, setpoint_steer_ang;
150  virtual void control_step(
155  co); // See base class docs
156  virtual void load_config(
157  const rapidxml::xml_node<char>& node); // See base class docs
158  virtual void teleop_interface(
159  const TeleopInput& in, TeleopOutput& out); // See base class docs
160 
161  double KP, KI, KD;
162  double max_torque;
163  private:
165  double m_r2f_L;
166  };
167 
168  const ControllerBasePtr& getController() const { return m_controller; }
169  ControllerBasePtr& getController() { return m_controller; }
171  {
172  return m_controller.get();
173  }
174  // end controllers
176 
177  virtual vec3 getVelocityLocalOdoEstimate() const; // See docs of base class
178 
185  const double desired_equiv_steer_ang, double& out_fl_ang,
186  double& out_fr_ang) const;
187 
191  const double w1, const double w2, const double diffBias,
192  const double defaultSplitRatio, double& t1, double& t2);
193 
194  protected:
195  // See base class docs
196  virtual void dynamics_load_params_from_xml(
197  const rapidxml::xml_node<char>* xml_node);
198  // See base class doc
199  virtual void invoke_motor_controllers(
200  const TSimulContext& context, std::vector<double>& out_force_per_wheel);
201 
202  private:
203  ControllerBasePtr m_controller;
204 
206 
209 
213 
216  double m_RearLRBias;
217 };
218 }
DifferentialType m_diff_type
min turning radius
double max_torque
Maximum abs. value torque (for clamp) [Nm].
ControllerBaseTempl< DynamicsAckermannDrivetrain > ControllerBase
void computeDiffTorqueSplit(const double w1, const double w2, const double diffBias, const double defaultSplitRatio, double &t1, double &t2)
const ControllerBasePtr & getController() const
virtual ControllerBaseInterface * getControllerInterface()
#define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME)
Definition: VehicleBase.h:296
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel)
std::shared_ptr< ControllerBase > ControllerBasePtr
double steer_ang
Equivalent ackerman steering angle.
ControllerBasePtr m_controller
The installed controller.
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)
double max_torque
Maximum abs. value torque (for clamp) [Nm].
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const


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