VehicleAckermann.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::DEG2RAD;
21 using mrpt::utils::keep_min;
22 using mrpt::utils::keep_max;
23 #else
24 #include <mrpt/img/TColor.h>
25 using mrpt::img::TColor;
26 using mrpt::DEG2RAD;
27 using mrpt::keep_min;
28 using mrpt::keep_max;
29 #endif
30 
31 namespace mvsim
32 {
37 {
39  public:
40  // Wheels: [0]:rear-left, [1]:rear-right, [2]: front-left, [3]: front-right
41  enum
42  {
43  WHEEL_RL = 0,
44  WHEEL_RR = 1,
45  WHEEL_FL = 2,
47  };
48 
49  DynamicsAckermann(World* parent);
50 
52  double getMaxSteeringAngle() const { return m_max_steer_ang; }
53  void setMaxSteeringAngle(double val) { m_max_steer_ang = val; }
58  {
60  };
62  {
63  double fl_torque, fr_torque, rl_torque, rr_torque;
64  double steer_ang;
66  : fl_torque(0),
67  fr_torque(0),
68  rl_torque(0),
69  rr_torque(0),
70  steer_ang(0)
71  {
72  }
73  };
74 
77  typedef std::shared_ptr<ControllerBase> ControllerBasePtr;
78 
79  class ControllerRawForces : public ControllerBase
80  {
81  public:
83  static const char* class_name() { return "raw"; }
86  double setpoint_wheel_torque_l, setpoint_wheel_torque_r,
87  setpoint_steer_ang;
88  virtual void control_step(
90  DynamicsAckermann::TControllerOutput& co); // See base class docs
91  virtual void load_config(
92  const rapidxml::xml_node<char>& node); // See base class docs
93  virtual void teleop_interface(
94  const TeleopInput& in, TeleopOutput& out); // See base class docs
95  };
96 
99  class ControllerTwistFrontSteerPID : public ControllerBase
100  {
101  public:
103  static const char* class_name() { return "twist_front_steer_pid"; }
107  setpoint_ang_speed;
108  virtual void control_step(
110  DynamicsAckermann::TControllerOutput& co); // See base class docs
111  virtual void load_config(
112  const rapidxml::xml_node<char>& node); // See base class docs
113  virtual void teleop_interface(
114  const TeleopInput& in, TeleopOutput& out); // See base class docs
115 
116  double KP, KI, KD;
117  double max_torque;
118 
119  // See base docs.
120  virtual bool setTwistCommand(const double vx, const double wz)
121  {
122  setpoint_lin_speed = vx;
123  setpoint_ang_speed = wz;
124  return true;
125  }
126 
127  private:
128  double m_dist_fWheels, m_r2f_L;
129  PID_Controller m_PID[2]; //<! [0]:fl, [1]: fr
130  };
131 
134  class ControllerFrontSteerPID : public ControllerBase
135  {
136  public:
138  static const char* class_name() { return "front_steer_pid"; }
141  double setpoint_lin_speed, setpoint_steer_ang;
142  virtual void control_step(
146  DynamicsAckermann::TControllerOutput& co); // See base class docs
147  virtual void load_config(
148  const rapidxml::xml_node<char>& node); // See base class docs
149  virtual void teleop_interface(
150  const TeleopInput& in, TeleopOutput& out); // See base class docs
151 
152  double KP, KI, KD;
153  double max_torque;
154  private:
156  double m_r2f_L;
157  };
158 
159  const ControllerBasePtr& getController() const { return m_controller; }
160  ControllerBasePtr& getController() { return m_controller; }
162  {
163  return m_controller.get();
164  }
165  // end controllers
167 
168  virtual vec3 getVelocityLocalOdoEstimate() const; // See docs of base class
169 
176  const double desired_equiv_steer_ang, double& out_fl_ang,
177  double& out_fr_ang) const;
178 
179  protected:
180  // See base class docs
181  virtual void dynamics_load_params_from_xml(
182  const rapidxml::xml_node<char>* xml_node);
183  // See base class doc
184  virtual void invoke_motor_controllers(
185  const TSimulContext& context, std::vector<double>& out_force_per_wheel);
186 
187  private:
188  ControllerBasePtr m_controller;
189 
191 };
193 }
virtual ControllerBaseInterface * getControllerInterface()
DynamicsAckermann(World *parent)
double max_torque
Maximum abs. value torque (for clamp) [Nm].
ControllerBasePtr m_controller
The installed controller.
const ControllerBasePtr & getController() const
void setMaxSteeringAngle(double val)
ControllerBaseTempl< DynamicsAckermann > ControllerBase
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)
virtual vec3 getVelocityLocalOdoEstimate() const
#define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME)
Definition: VehicleBase.h:296
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.
virtual bool setTwistCommand(const double vx, const double wz)
double getMaxSteeringAngle() const
double max_torque
Maximum abs. value torque (for clamp) [Nm].
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