VehicleBase.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 <mutex>
13 
14 #include <mvsim/basic_types.h>
15 #include <mvsim/VisualObject.h>
16 #include <mvsim/Simulable.h>
17 #include <mvsim/Wheel.h>
18 #include <mvsim/ClassFactory.h>
21 #include <mvsim/ControllerBase.h>
22 
23 #include <Box2D/Dynamics/b2World.h>
24 #include <Box2D/Dynamics/b2Body.h>
27 
28 #include <mrpt/poses/CPose2D.h>
29 
30 #include <mrpt/opengl/CSetOfObjects.h>
31 #include <mrpt/opengl/CSetOfLines.h>
32 #if MRPT_VERSION<0x199
33 #include <mrpt/utils/TColor.h>
34 using mrpt::utils::TColor;
35 #else
36 #include <mrpt/img/TColor.h>
37 using mrpt::img::TColor;
38 #endif
39 
40 #include <string>
41 #include <map>
42 #include "CsvLogger.h"
43 
44 namespace mvsim
45 {
50 class VehicleBase : public VisualObject, public Simulable
51 {
52  public:
55  static VehicleBase* factory(
56  World* parent, const rapidxml::xml_node<char>* xml_node);
58  static VehicleBase* factory(World* parent, const std::string& xml_text);
59 
62  static void register_vehicle_class(
63  const rapidxml::xml_node<char>* xml_node);
64 
65  // ------- Interface with "World" ------
66  virtual void simul_pre_timestep(
67  const TSimulContext& context); // See derived class docs
68  virtual void simul_post_timestep(
69  const TSimulContext& context); // See derived class docs
70  virtual void apply_force(
71  double fx, double fy, double local_ptx = 0.0,
72  double local_pty = 0.0); // See derived class docs
73 
75  void simul_post_timestep_common(const TSimulContext& context);
76 
79  virtual void create_multibody_system(b2World* world);
80 
83  virtual float getMaxVehicleRadius() const { return m_max_radius; }
85  virtual double getChassisMass() const { return m_chassis_mass; }
86  b2Body* getBox2DChassisBody() { return m_b2d_vehicle_body; }
87  mrpt::math::TPoint2D getChassisCenterOfMass() const
88  {
89  return m_chassis_com;
90  }
91 
92  size_t getNumWheels() const { return m_wheels_info.size(); }
93  const Wheel& getWheelInfo(const size_t idx) const
94  {
95  return m_wheels_info[idx];
96  }
97  Wheel& getWheelInfo(const size_t idx) { return m_wheels_info[idx]; }
98  const mrpt::math::TPose3D& getPose() const
99  {
100  return m_q;
101  }
102  void setPose(const mrpt::math::TPose3D& p) const
104  {
105  const_cast<mrpt::math::TPose3D&>(m_q) = p;
106  }
107 
109  mrpt::poses::CPose2D getCPose2D() const;
110 
112  const vec3& getVelocity() const { return m_dq; }
116  vec3 getVelocityLocal() const;
120  std::vector<mrpt::math::TPoint2D>& vels,
121  const vec3& veh_vel_local) const;
122 
127  virtual vec3 getVelocityLocalOdoEstimate() const = 0;
128 
129  typedef std::vector<SensorBase::Ptr> TListSensors;
130 
131  const TListSensors& getSensors() const { return m_sensors; }
132  TListSensors& getSensors() { return m_sensors; }
133  std::shared_ptr<CSVLogger> getLoggerPtr(std::string logger_name)
134  {
135  return m_loggers[logger_name];
136  }
137 
139  const std::string& getName() const { return m_name; }
142  const mrpt::math::TPolygon2D& getChassisShape() const
143  {
144  return m_chassis_poly;
145  }
146 
148  void setVehicleIndex(size_t idx) { m_vehicle_index = idx; }
150  size_t getVehicleIndex() const { return m_vehicle_index; }
151  void setRecording(bool record)
152  {
153  for (auto& logger : m_loggers) logger.second->setRecording(record);
154  }
155  void clearLogs()
156  {
157  for (auto& logger : m_loggers) logger.second->clear();
158  }
160  {
161  for (auto& logger : m_loggers) logger.second->newSession();
162  }
163 
170  virtual void gui_update(mrpt::opengl::COpenGLScene& scene);
171 
173 
174  protected:
175  std::map<std::string, std::shared_ptr<CSVLogger>> m_loggers;
176  std::string m_log_path;
177 
178  virtual void initLoggers();
179  virtual void writeLogStrings();
180 
181  protected:
182  // Protected ctor for class factory
183  VehicleBase(World* parent, size_t nWheels);
184 
188  virtual void dynamics_load_params_from_xml(
189  const rapidxml::xml_node<char>* xml_node) = 0;
190 
191  virtual void invoke_motor_controllers(
192  const TSimulContext& context,
193  std::vector<double>& out_force_per_wheel) = 0;
194 
201  void gui_update_common(
202  mrpt::opengl::COpenGLScene& scene, bool defaultVehicleBody = true);
203 
204  std::string
207 
215  b2Body* m_b2d_vehicle_body;
216 
217  FrictionBasePtr m_friction;
218 
220  TListSensors m_sensors;
221 
222  mrpt::math::TPose3D
223  m_q;
224  vec3 m_dq;
225 
227  std::vector<double>
228  m_torque_per_wheel;
229 
230  // Chassis info:
231  double m_chassis_mass;
232  mrpt::math::TPolygon2D m_chassis_poly;
233  double m_max_radius;
234  double m_chassis_z_min, m_chassis_z_max;
236  TColor m_chassis_color;
237 
238  mrpt::math::TPoint2D m_chassis_com;
239 
241  void updateMaxRadiusFromPoly();
242 
243  // Wheels info:
244  std::vector<Wheel> m_wheels_info;
245 
249  // Box2D elements:
250  b2Fixture* m_fixture_chassis;
251  std::vector<b2Fixture*> m_fixture_wheels;
252 
255  private:
256  void internal_gui_update_sensors(
257  mrpt::opengl::COpenGLScene&
258  scene);
259  void internal_gui_update_forces(
260  mrpt::opengl::COpenGLScene&
261  scene);
262 
263  mrpt::opengl::CSetOfObjects::Ptr m_gl_chassis;
264  std::vector<mrpt::opengl::CSetOfObjects::Ptr> m_gl_wheels;
265  mrpt::opengl::CSetOfLines::Ptr m_gl_forces;
266  std::mutex m_force_segments_for_rendering_cs;
267  std::vector<mrpt::math::TSegment3D> m_force_segments_for_rendering;
268 
269  public: // data logger header entries
270  static constexpr char DL_TIMESTAMP[] = "timestamp";
271  static constexpr char LOGGER_POSE[] = "logger_pose";
272  static constexpr char LOGGER_WHEEL[] = "logger_wheel";
273 
274  static constexpr char PL_Q_X[] = "Qx";
275  static constexpr char PL_Q_Y[] = "Qy";
276  static constexpr char PL_Q_Z[] = "Qz";
277  static constexpr char PL_Q_YAW[] = "Qyaw";
278  static constexpr char PL_Q_PITCH[] = "Qpitch";
279  static constexpr char PL_Q_ROLL[] = "Qroll";
280  static constexpr char PL_DQ_X[] = "dQx";
281  static constexpr char PL_DQ_Y[] = "dQy";
282  static constexpr char PL_DQ_Z[] = "dQz";
283 
284  static constexpr char WL_TORQUE[] = "torque";
285  static constexpr char WL_WEIGHT[] = "weight";
286  static constexpr char WL_VEL_X[] = "velocity_x";
287  static constexpr char WL_VEL_Y[] = "velocity_y";
288  static constexpr char WL_FRIC_X[] = "friction_x";
289  static constexpr char WL_FRIC_Y[] = "friction_y";
290 }; // end VehicleBase
291 
292 // Class factory:
294 extern TClassFactory_vehicleDynamics classFactory_vehicleDynamics;
295 
296 #define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME) \
297  DECLARES_REGISTER_CLASS1(CLASS_NAME, VehicleBase, World*)
298 
299 #define REGISTER_VEHICLE_DYNAMICS(TEXTUAL_NAME, CLASS_NAME) \
300  REGISTER_CLASS1( \
301  TClassFactory_vehicleDynamics, classFactory_vehicleDynamics, \
302  TEXTUAL_NAME, CLASS_NAME)
303 }
virtual void create_multibody_system(b2World *world)
b2Body * getBox2DChassisBody()
Definition: VehicleBase.h:86
void setPose(const mrpt::math::TPose3D &p) const
Definition: VehicleBase.h:103
ClassFactory< VehicleBase, World * > TClassFactory_vehicleDynamics
Definition: VehicleBase.h:293
void getWheelsVelocityLocal(std::vector< mrpt::math::TPoint2D > &vels, const vec3 &veh_vel_local) const
const std::string & getName() const
Definition: VehicleBase.h:139
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)=0
virtual void initLoggers()
std::shared_ptr< FrictionBase > FrictionBasePtr
Definition: FrictionBase.h:70
virtual void apply_force(double fx, double fy, double local_ptx=0.0, double local_pty=0.0)
virtual vec3 getVelocityLocalOdoEstimate() const =0
std::shared_ptr< CSVLogger > getLoggerPtr(std::string logger_name)
Definition: VehicleBase.h:133
virtual void simul_post_timestep(const TSimulContext &context)
std::string m_log_path
Definition: VehicleBase.h:176
const TListSensors & getSensors() const
Definition: VehicleBase.h:131
const mrpt::math::TPolygon2D & getChassisShape() const
Definition: VehicleBase.h:142
TClassFactory_vehicleDynamics classFactory_vehicleDynamics
Definition: VehicleBase.cpp:37
size_t getNumWheels() const
Definition: VehicleBase.h:92
A rigid body. These are created via b2World::CreateBody.
Definition: b2Body.h:126
VehicleBase(World *parent, size_t nWheels)
Definition: VehicleBase.cpp:77
Wheel & getWheelInfo(const size_t idx)
Definition: VehicleBase.h:97
size_t getVehicleIndex() const
Definition: VehicleBase.h:150
virtual void simul_pre_timestep(const TSimulContext &context)
virtual ControllerBaseInterface * getControllerInterface()=0
virtual float getMaxVehicleRadius() const
Definition: VehicleBase.h:83
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:175
const Wheel & getWheelInfo(const size_t idx) const
Definition: VehicleBase.h:93
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel)=0
void gui_update_common(mrpt::opengl::COpenGLScene &scene, bool defaultVehicleBody=true)
void setRecording(bool record)
Definition: VehicleBase.h:151
const mrpt::math::TPose3D & getPose() const
Definition: VehicleBase.h:98
virtual void gui_update(mrpt::opengl::COpenGLScene &scene)
std::vector< SensorBase::Ptr > TListSensors
Definition: VehicleBase.h:129
virtual void writeLogStrings()
void simul_post_timestep_common(const TSimulContext &context)
TListSensors & getSensors()
Definition: VehicleBase.h:132
void setVehicleIndex(size_t idx)
Definition: VehicleBase.h:148
mrpt::poses::CPose2D getCPose2D() const
vec3 getVelocityLocal() const
virtual double getChassisMass() const
Definition: VehicleBase.h:85
const vec3 & getVelocity() const
Definition: VehicleBase.h:112
mrpt::math::TPoint2D getChassisCenterOfMass() const
In local coordinates (this excludes the mass of wheels)
Definition: VehicleBase.h:87
std::string m_name
User-supplied name of the vehicle (e.g. "r1", "veh1")
Definition: VehicleBase.h:205
static VehicleBase * factory(World *parent, const rapidxml::xml_node< char > *xml_node)


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