VehicleBase.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 
13 #include <Box2D/Dynamics/b2Body.h>
15 #include <Box2D/Dynamics/b2World.h>
16 #include <mrpt/img/TColor.h>
19 #include <mrpt/poses/CPose2D.h>
20 #include <mvsim/ClassFactory.h>
21 #include <mvsim/ControllerBase.h>
24 #include <mvsim/Simulable.h>
25 #include <mvsim/VisualObject.h>
26 #include <mvsim/Wheel.h>
27 #include <mvsim/basic_types.h>
28 
29 #include <map>
30 #include <mutex>
31 #include <string>
32 
33 #include "CsvLogger.h"
34 
35 namespace mvsim
36 {
41 class VehicleBase : public VisualObject, public Simulable
42 {
43  public:
44  using Ptr = std::shared_ptr<VehicleBase>;
45 
48  static Ptr factory(World* parent, const rapidxml::xml_node<char>* xml_node);
50  static Ptr factory(World* parent, const std::string& xml_text);
51 
54  static void register_vehicle_class(
55  const rapidxml::xml_node<char>* xml_node);
56 
57  void poses_mutex_lock() override { m_gui_mtx.lock(); }
58  void poses_mutex_unlock() override { m_gui_mtx.unlock(); }
59 
60  // ------- Interface with "World" ------
61  virtual void simul_pre_timestep(const TSimulContext& context) override;
62  virtual void simul_post_timestep(const TSimulContext& context) override;
63  virtual void apply_force(
64  const mrpt::math::TVector2D& force,
65  const mrpt::math::TPoint2D& applyPoint =
66  mrpt::math::TPoint2D(0, 0)) override;
67 
70  virtual void create_multibody_system(b2World& world);
71 
74  virtual float getMaxVehicleRadius() const { return m_max_radius; }
76  virtual double getChassisMass() const { return m_chassis_mass; }
77  b2Body* getBox2DChassisBody() { return m_b2d_body; }
79  {
80  return m_chassis_com;
81  }
82 
83  size_t getNumWheels() const { return m_wheels_info.size(); }
84  const Wheel& getWheelInfo(const size_t idx) const
85  {
86  return m_wheels_info[idx];
87  }
88  Wheel& getWheelInfo(const size_t idx) { return m_wheels_info[idx]; }
89 
93  std::vector<mrpt::math::TPoint2D>& vels,
94  const mrpt::math::TTwist2D& veh_vel_local) const;
95 
101 
102  typedef std::vector<SensorBase::Ptr> TListSensors;
103 
104  const TListSensors& getSensors() const { return m_sensors; }
105  TListSensors& getSensors() { return m_sensors; }
106  std::shared_ptr<CSVLogger> getLoggerPtr(std::string logger_name)
107  {
108  return m_loggers[logger_name];
109  }
110 
114  {
115  return m_chassis_poly;
116  }
117 
119  void setVehicleIndex(size_t idx) { m_vehicle_index = idx; }
121  size_t getVehicleIndex() const { return m_vehicle_index; }
122  void setRecording(bool record)
123  {
124  for (auto& logger : m_loggers) logger.second->setRecording(record);
125  }
126  void clearLogs()
127  {
128  for (auto& logger : m_loggers) logger.second->clear();
129  }
131  {
132  for (auto& logger : m_loggers) logger.second->newSession();
133  }
134 
136 
137  void registerOnServer(mvsim::Client& c) override;
138 
140  std::vector<b2Fixture*>& get_fixture_wheels() { return m_fixture_wheels; }
142  const std::vector<b2Fixture*>& get_fixture_wheels() const
143  {
144  return m_fixture_wheels;
145  }
146 
147  protected:
148  std::map<std::string, std::shared_ptr<CSVLogger>> m_loggers;
149  std::string m_log_path;
150 
151  virtual void initLoggers();
152  virtual void writeLogStrings();
153  virtual void internalGuiUpdate(
154  mrpt::opengl::COpenGLScene& scene, bool childrenOnly) override;
156 
157  protected:
158  // Protected ctor for class factory
159  VehicleBase(World* parent, size_t nWheels);
160 
164  virtual void dynamics_load_params_from_xml(
165  const rapidxml::xml_node<char>* xml_node) = 0;
166 
167  virtual void invoke_motor_controllers(
168  const TSimulContext& context,
169  std::vector<double>& out_force_per_wheel) = 0;
170 
174 
177 
178  TListSensors m_sensors;
179 
181  std::vector<double> m_torque_per_wheel;
182 
183  // Chassis info:
186  double m_max_radius;
189  mrpt::img::TColor m_chassis_color;
190 
192 
195 
196  // Wheels info:
197  std::vector<Wheel> m_wheels_info;
198 
202  // Box2D elements:
204  std::vector<b2Fixture*> m_fixture_wheels;
205 
208  private:
209  // Called from internalGuiUpdate_common()
211  // Called from internalGuiUpdate_common()
213 
214  mrpt::opengl::CSetOfObjects::Ptr m_gl_chassis;
215  std::vector<mrpt::opengl::CSetOfObjects::Ptr> m_gl_wheels;
216  mrpt::opengl::CSetOfLines::Ptr m_gl_forces;
218  std::vector<mrpt::math::TSegment3D> m_force_segments_for_rendering;
219 
220  std::mutex m_gui_mtx;
221 
222  public: // data logger header entries
223  static constexpr char DL_TIMESTAMP[] = "timestamp";
224  static constexpr char LOGGER_POSE[] = "logger_pose";
225  static constexpr char LOGGER_WHEEL[] = "logger_wheel";
226 
227  static constexpr char PL_Q_X[] = "Qx";
228  static constexpr char PL_Q_Y[] = "Qy";
229  static constexpr char PL_Q_Z[] = "Qz";
230  static constexpr char PL_Q_YAW[] = "Qyaw";
231  static constexpr char PL_Q_PITCH[] = "Qpitch";
232  static constexpr char PL_Q_ROLL[] = "Qroll";
233  static constexpr char PL_DQ_X[] = "dQx";
234  static constexpr char PL_DQ_Y[] = "dQy";
235  static constexpr char PL_DQ_Z[] = "dQz";
236 
237  static constexpr char WL_TORQUE[] = "torque";
238  static constexpr char WL_WEIGHT[] = "weight";
239  static constexpr char WL_VEL_X[] = "velocity_x";
240  static constexpr char WL_VEL_Y[] = "velocity_y";
241  static constexpr char WL_FRIC_X[] = "friction_x";
242  static constexpr char WL_FRIC_Y[] = "friction_y";
243 }; // end VehicleBase
244 
245 // Class factory:
247 extern TClassFactory_vehicleDynamics classFactory_vehicleDynamics;
248 
249 #define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME) \
250  DECLARES_REGISTER_CLASS1(CLASS_NAME, VehicleBase, World*)
251 
252 #define REGISTER_VEHICLE_DYNAMICS(TEXTUAL_NAME, CLASS_NAME) \
253  REGISTER_CLASS1( \
254  TClassFactory_vehicleDynamics, classFactory_vehicleDynamics, \
255  TEXTUAL_NAME, CLASS_NAME)
256 } // namespace mvsim
void getWheelsVelocityLocal(std::vector< mrpt::math::TPoint2D > &vels, const mrpt::math::TTwist2D &veh_vel_local) const
mrpt::img::TColor m_chassis_color
Definition: VehicleBase.h:189
void internal_internalGuiUpdate_forces(mrpt::opengl::COpenGLScene &scene)
b2Body * getBox2DChassisBody()
Definition: VehicleBase.h:77
mrpt::opengl::CSetOfObjects::Ptr m_gl_chassis
Definition: VehicleBase.h:214
void updateMaxRadiusFromPoly()
excludes the mass of wheels)
static constexpr char PL_DQ_Y[]
Definition: VehicleBase.h:234
static Ptr factory(World *parent, const rapidxml::xml_node< char > *xml_node)
ClassFactory< VehicleBase, World * > TClassFactory_vehicleDynamics
Definition: VehicleBase.h:246
b2Fixture * get_fixture_chassis()
Definition: VehicleBase.h:139
const GLfloat * c
static constexpr char PL_Q_ROLL[]
Definition: VehicleBase.h:232
virtual void simul_post_timestep(const TSimulContext &context) override
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)=0
virtual void initLoggers()
void poses_mutex_lock() override
Definition: VehicleBase.h:57
static constexpr char LOGGER_WHEEL[]
Definition: VehicleBase.h:225
std::vector< double > m_torque_per_wheel
Definition: VehicleBase.h:181
static constexpr char WL_VEL_X[]
Definition: VehicleBase.h:239
std::shared_ptr< FrictionBase > FrictionBasePtr
Definition: FrictionBase.h:71
std::shared_ptr< CSVLogger > getLoggerPtr(std::string logger_name)
Definition: VehicleBase.h:106
static constexpr char PL_Q_X[]
Definition: VehicleBase.h:227
static constexpr char WL_TORQUE[]
Definition: VehicleBase.h:237
virtual void internalGuiUpdate(mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override
const b2Fixture * get_fixture_chassis() const
Definition: VehicleBase.h:141
std::string m_log_path
Definition: VehicleBase.h:149
static constexpr char PL_Q_Z[]
Definition: VehicleBase.h:229
static constexpr char PL_Q_PITCH[]
Definition: VehicleBase.h:231
const TListSensors & getSensors() const
Definition: VehicleBase.h:104
std::vector< mrpt::math::TSegment3D > m_force_segments_for_rendering
Definition: VehicleBase.h:218
const mrpt::math::TPolygon2D & getChassisShape() const
Definition: VehicleBase.h:113
TClassFactory_vehicleDynamics classFactory_vehicleDynamics
Definition: VehicleBase.cpp:38
static constexpr char PL_Q_YAW[]
Definition: VehicleBase.h:230
static constexpr char PL_DQ_Z[]
Definition: VehicleBase.h:235
size_t getNumWheels() const
Definition: VehicleBase.h:83
A rigid body. These are created via b2World::CreateBody.
Definition: b2Body.h:126
VehicleBase(World *parent, size_t nWheels)
Definition: VehicleBase.cpp:78
Wheel & getWheelInfo(const size_t idx)
Definition: VehicleBase.h:88
void internal_internalGuiUpdate_sensors(mrpt::opengl::COpenGLScene &scene)
virtual void create_multibody_system(b2World &world)
size_t getVehicleIndex() const
Definition: VehicleBase.h:121
std::shared_ptr< VehicleBase > Ptr
Definition: VehicleBase.h:44
mrpt::opengl::CSetOfLines::Ptr m_gl_forces
Definition: VehicleBase.h:216
std::mutex m_force_segments_for_rendering_cs
Definition: VehicleBase.h:217
void poses_mutex_unlock() override
Definition: VehicleBase.h:58
static constexpr char PL_Q_Y[]
Definition: VehicleBase.h:228
static constexpr char WL_FRIC_X[]
Definition: VehicleBase.h:241
virtual ControllerBaseInterface * getControllerInterface()=0
static constexpr char PL_DQ_X[]
Definition: VehicleBase.h:233
virtual float getMaxVehicleRadius() const
Definition: VehicleBase.h:74
static void register_vehicle_class(const rapidxml::xml_node< char > *xml_node)
std::map< std::string, std::shared_ptr< CSVLogger > > m_loggers
Definition: VehicleBase.h:148
void registerOnServer(mvsim::Client &c) override
TListSensors m_sensors
Sensors aboard.
Definition: VehicleBase.h:178
const Wheel & getWheelInfo(const size_t idx) const
Definition: VehicleBase.h:84
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel)=0
std::vector< Wheel > m_wheels_info
Definition: VehicleBase.h:197
void setRecording(bool record)
Definition: VehicleBase.h:122
std::vector< mrpt::opengl::CSetOfObjects::Ptr > m_gl_wheels
Definition: VehicleBase.h:215
std::vector< SensorBase::Ptr > TListSensors
Definition: VehicleBase.h:102
std::vector< b2Fixture * > & get_fixture_wheels()
Definition: VehicleBase.h:140
virtual void writeLogStrings()
virtual mrpt::poses::CPose3D internalGuiGetVisualPose() override
TListSensors & getSensors()
Definition: VehicleBase.h:105
const std::vector< b2Fixture * > & get_fixture_wheels() const
Definition: VehicleBase.h:142
std::mutex m_gui_mtx
Definition: VehicleBase.h:220
static constexpr char WL_VEL_Y[]
Definition: VehicleBase.h:240
std::vector< b2Fixture * > m_fixture_wheels
Definition: VehicleBase.h:204
static constexpr char LOGGER_POSE[]
Definition: VehicleBase.h:224
double m_chassis_z_min
each change via updateMaxRadiusFromPoly()
Definition: VehicleBase.h:188
void setVehicleIndex(size_t idx)
Definition: VehicleBase.h:119
static constexpr char WL_WEIGHT[]
Definition: VehicleBase.h:238
mrpt::math::TPoint2D m_chassis_com
Definition: VehicleBase.h:191
mrpt::math::TPolygon2D m_chassis_poly
Definition: VehicleBase.h:185
static constexpr char WL_FRIC_Y[]
Definition: VehicleBase.h:242
b2Fixture * m_fixture_chassis
Created at.
Definition: VehicleBase.h:203
virtual void apply_force(const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) override
virtual double getChassisMass() const
Definition: VehicleBase.h:76
FrictionBasePtr m_friction
Definition: VehicleBase.h:176
mrpt::math::TPoint2D getChassisCenterOfMass() const
In local coordinates (this excludes the mass of wheels)
Definition: VehicleBase.h:78
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const =0
static constexpr char DL_TIMESTAMP[]
Definition: VehicleBase.h:223
virtual void simul_pre_timestep(const TSimulContext &context) override


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