VehicleBase.h
Go to the documentation of this file.
00001 /*+-------------------------------------------------------------------------+
00002   |                       MultiVehicle simulator (libmvsim)                 |
00003   |                                                                         |
00004   | Copyright (C) 2014  Jose Luis Blanco Claraco (University of Almeria)    |
00005   | Copyright (C) 2017  Borys Tymchenko (Odessa Polytechnic University)     |
00006   | Distributed under GNU General Public License version 3                  |
00007   |   See <http://www.gnu.org/licenses/>                                    |
00008   +-------------------------------------------------------------------------+ */
00009 
00010 #pragma once
00011 
00012 #include <mutex>
00013 
00014 #include <mvsim/basic_types.h>
00015 #include <mvsim/VisualObject.h>
00016 #include <mvsim/Simulable.h>
00017 #include <mvsim/Wheel.h>
00018 #include <mvsim/ClassFactory.h>
00019 #include <mvsim/FrictionModels/FrictionBase.h>
00020 #include <mvsim/Sensors/SensorBase.h>
00021 #include <mvsim/ControllerBase.h>
00022 
00023 #include <Box2D/Dynamics/b2World.h>
00024 #include <Box2D/Dynamics/b2Body.h>
00025 #include <Box2D/Collision/Shapes/b2PolygonShape.h>
00026 #include <Box2D/Dynamics/b2Fixture.h>
00027 
00028 #include <mrpt/poses/CPose2D.h>
00029 
00030 #include <mrpt/opengl/CSetOfObjects.h>
00031 #include <mrpt/opengl/CSetOfLines.h>
00032 #include <mrpt/utils/TColor.h>
00033 
00034 #include <string>
00035 #include <map>
00036 #include "CsvLogger.h"
00037 
00038 namespace mvsim
00039 {
00044 class VehicleBase : public VisualObject, public Simulable
00045 {
00046    public:
00049         static VehicleBase* factory(
00050                 World* parent, const rapidxml::xml_node<char>* xml_node);
00052         static VehicleBase* factory(World* parent, const std::string& xml_text);
00053 
00056         static void register_vehicle_class(
00057                 const rapidxml::xml_node<char>* xml_node);
00058 
00059         // ------- Interface with "World" ------
00060         virtual void simul_pre_timestep(
00061                 const TSimulContext& context);  // See derived class docs
00062         virtual void simul_post_timestep(
00063                 const TSimulContext& context);  // See derived class docs
00064         virtual void apply_force(
00065                 double fx, double fy, double local_ptx = 0.0,
00066                 double local_pty = 0.0);  // See derived class docs
00067 
00069         void simul_post_timestep_common(const TSimulContext& context);
00070 
00073         virtual void create_multibody_system(b2World* world);
00074 
00077         virtual float getMaxVehicleRadius() const { return m_max_radius; }
00079         virtual double getChassisMass() const { return m_chassis_mass; }
00080         b2Body* getBox2DChassisBody() { return m_b2d_vehicle_body; }
00081         mrpt::math::TPoint2D getChassisCenterOfMass() const
00082         {
00083                 return m_chassis_com;
00084         }  
00085 
00086         size_t getNumWheels() const { return m_wheels_info.size(); }
00087         const Wheel& getWheelInfo(const size_t idx) const
00088         {
00089                 return m_wheels_info[idx];
00090         }
00091         Wheel& getWheelInfo(const size_t idx) { return m_wheels_info[idx]; }
00092         const mrpt::math::TPose3D& getPose() const
00093         {
00094                 return m_q;
00095         }  
00096 
00097         void setPose(const mrpt::math::TPose3D& p) const
00098         {
00099                 const_cast<mrpt::math::TPose3D&>(m_q) = p;
00100         }  
00101 
00102 
00103         mrpt::poses::CPose2D getCPose2D() const;  
00104 
00106         const vec3& getVelocity() const { return m_dq; }
00110         vec3 getVelocityLocal() const;
00113         void getWheelsVelocityLocal(
00114                 std::vector<mrpt::math::TPoint2D>& vels,
00115                 const vec3& veh_vel_local) const;
00116 
00121         virtual vec3 getVelocityLocalOdoEstimate() const = 0;
00122 
00123         typedef std::vector<SensorBase::Ptr> TListSensors;
00124 
00125         const TListSensors& getSensors() const { return m_sensors; }
00126         TListSensors& getSensors() { return m_sensors; }
00127         std::shared_ptr<CSVLogger> getLoggerPtr(std::string logger_name)
00128         {
00129                 return m_loggers[logger_name];
00130         }
00131 
00133         const std::string& getName() const { return m_name; }
00136         const mrpt::math::TPolygon2D& getChassisShape() const
00137         {
00138                 return m_chassis_poly;
00139         }
00140 
00142         void setVehicleIndex(size_t idx) { m_vehicle_index = idx; }
00144         size_t getVehicleIndex() const { return m_vehicle_index; }
00145         void setRecording(bool record)
00146         {
00147                 for (auto& logger : m_loggers) logger.second->setRecording(record);
00148         }
00149         void clearLogs()
00150         {
00151                 for (auto& logger : m_loggers) logger.second->clear();
00152         }
00153         void newLogSession()
00154         {
00155                 for (auto& logger : m_loggers) logger.second->newSession();
00156         }
00157 
00164         virtual void gui_update(mrpt::opengl::COpenGLScene& scene);
00165 
00166         virtual ControllerBaseInterface* getControllerInterface() = 0;
00167 
00168    protected:
00169         std::map<std::string, std::shared_ptr<CSVLogger>> m_loggers;
00170         std::string m_log_path;
00171 
00172         virtual void initLoggers();
00173         virtual void writeLogStrings();
00174 
00175    protected:
00176         // Protected ctor for class factory
00177         VehicleBase(World* parent, size_t nWheels);
00178 
00182         virtual void dynamics_load_params_from_xml(
00183                 const rapidxml::xml_node<char>* xml_node) = 0;
00184 
00185         virtual void invoke_motor_controllers(
00186                 const TSimulContext& context,
00187                 std::vector<double>& out_force_per_wheel) = 0;
00188 
00195         void gui_update_common(
00196                 mrpt::opengl::COpenGLScene& scene, bool defaultVehicleBody = true);
00197 
00198         std::string
00199                 m_name;  
00200         size_t m_vehicle_index;  
00201 
00202 
00203 
00209         b2Body* m_b2d_vehicle_body;
00210 
00211         FrictionBasePtr m_friction;  
00212 
00213 
00214         TListSensors m_sensors;  
00215 
00216         mrpt::math::TPose3D
00217                 m_q;  
00218         vec3 m_dq;  
00219 
00220 
00221         std::vector<double>
00222                 m_torque_per_wheel;  
00223 
00224         // Chassis info:
00225         double m_chassis_mass;
00226         mrpt::math::TPolygon2D m_chassis_poly;
00227         double m_max_radius;  
00228 
00229         double m_chassis_z_min, m_chassis_z_max;
00230         mrpt::utils::TColor m_chassis_color;
00231 
00232         mrpt::math::TPoint2D m_chassis_com;  
00233 
00234 
00235         void updateMaxRadiusFromPoly();
00236 
00237         // Wheels info:
00238         std::vector<Wheel> m_wheels_info;  
00239 
00240 
00241 
00242 
00243         // Box2D elements:
00244         b2Fixture* m_fixture_chassis;  
00245         std::vector<b2Fixture*> m_fixture_wheels;  
00246 
00247 
00248 
00249    private:
00250         void internal_gui_update_sensors(
00251                 mrpt::opengl::COpenGLScene&
00252                         scene);  
00253         void internal_gui_update_forces(
00254                 mrpt::opengl::COpenGLScene&
00255                         scene);  
00256 
00257         mrpt::opengl::CSetOfObjects::Ptr m_gl_chassis;
00258         std::vector<mrpt::opengl::CSetOfObjects::Ptr> m_gl_wheels;
00259         mrpt::opengl::CSetOfLines::Ptr m_gl_forces;
00260         std::mutex m_force_segments_for_rendering_cs;
00261         std::vector<mrpt::math::TSegment3D> m_force_segments_for_rendering;
00262 
00263    public:  // data logger header entries
00264         static constexpr char DL_TIMESTAMP[] = "timestamp";
00265         static constexpr char LOGGER_POSE[] = "logger_pose";
00266         static constexpr char LOGGER_WHEEL[] = "logger_wheel";
00267 
00268         static constexpr char PL_Q_X[] = "Qx";
00269         static constexpr char PL_Q_Y[] = "Qy";
00270         static constexpr char PL_Q_Z[] = "Qz";
00271         static constexpr char PL_Q_YAW[] = "Qyaw";
00272         static constexpr char PL_Q_PITCH[] = "Qpitch";
00273         static constexpr char PL_Q_ROLL[] = "Qroll";
00274         static constexpr char PL_DQ_X[] = "dQx";
00275         static constexpr char PL_DQ_Y[] = "dQy";
00276         static constexpr char PL_DQ_Z[] = "dQz";
00277 
00278         static constexpr char WL_TORQUE[] = "torque";
00279         static constexpr char WL_WEIGHT[] = "weight";
00280         static constexpr char WL_VEL_X[] = "velocity_x";
00281         static constexpr char WL_VEL_Y[] = "velocity_y";
00282         static constexpr char WL_FRIC_X[] = "friction_x";
00283         static constexpr char WL_FRIC_Y[] = "friction_y";
00284 };  // end VehicleBase
00285 
00286 // Class factory:
00287 typedef ClassFactory<VehicleBase, World*> TClassFactory_vehicleDynamics;
00288 extern TClassFactory_vehicleDynamics classFactory_vehicleDynamics;
00289 
00290 #define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME) \
00291         DECLARES_REGISTER_CLASS1(CLASS_NAME, VehicleBase, World*)
00292 
00293 #define REGISTER_VEHICLE_DYNAMICS(TEXTUAL_NAME, CLASS_NAME)          \
00294         REGISTER_CLASS1(                                                 \
00295                 TClassFactory_vehicleDynamics, classFactory_vehicleDynamics, \
00296                 TEXTUAL_NAME, CLASS_NAME)
00297 }


mvsim
Author(s):
autogenerated on Thu Sep 7 2017 09:27:48