Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
mvsim::VehicleBase Class Referenceabstract

#include <VehicleBase.h>

Inheritance diagram for mvsim::VehicleBase:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< VehicleBase >
 
typedef std::vector< SensorBase::PtrTListSensors
 
- Public Types inherited from mvsim::Simulable
using Ptr = std::shared_ptr< Simulable >
 

Public Member Functions

virtual void apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) override
 
void clearLogs ()
 
virtual void create_multibody_system (b2World &world)
 
b2Fixtureget_fixture_chassis ()
 
const b2Fixtureget_fixture_chassis () const
 
std::vector< b2Fixture * > & get_fixture_wheels ()
 
const std::vector< b2Fixture * > & get_fixture_wheels () const
 
b2BodygetBox2DChassisBody ()
 
mrpt::math::TPoint2D getChassisCenterOfMass () const
 In local coordinates (this excludes the mass of wheels) More...
 
virtual double getChassisMass () const
 
const mrpt::math::TPolygon2DgetChassisShape () const
 
virtual ControllerBaseInterfacegetControllerInterface ()=0
 
std::shared_ptr< CSVLoggergetLoggerPtr (std::string logger_name)
 
virtual float getMaxVehicleRadius () const
 
size_t getNumWheels () const
 
const TListSensorsgetSensors () const
 
TListSensorsgetSensors ()
 
size_t getVehicleIndex () const
 
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate () const =0
 
const WheelgetWheelInfo (const size_t idx) const
 
WheelgetWheelInfo (const size_t idx)
 
void getWheelsVelocityLocal (std::vector< mrpt::math::TPoint2D > &vels, const mrpt::math::TTwist2D &veh_vel_local) const
 
void newLogSession ()
 
void poses_mutex_lock () override
 
void poses_mutex_unlock () override
 
void registerOnServer (mvsim::Client &c) override
 
void setRecording (bool record)
 
void setVehicleIndex (size_t idx)
 
virtual void simul_post_timestep (const TSimulContext &context) override
 
virtual void simul_pre_timestep (const TSimulContext &context) override
 
- Public Member Functions inherited from mvsim::VisualObject
void getVisualModelBoundingBox (mrpt::math::TPoint3D &bbmin, mrpt::math::TPoint3D &bbmax) const
 
WorldgetWorldObject ()
 
const WorldgetWorldObject () const
 
virtual void guiUpdate (mrpt::opengl::COpenGLScene &scene)
 
void showBoundingBox (bool show)
 
 VisualObject (World *parent)
 
virtual ~VisualObject ()
 
- Public Member Functions inherited from mvsim::Simulable
const b2Bodyb2d_body () const
 
b2Bodyb2d_body ()
 
mrpt::poses::CPose2D getCPose2D () const
 Alternative to getPose() More...
 
const std::stringgetName () const
 
mrpt::math::TPose3D getPose () const
 
mrpt::math::TTwist2D getTwist () const
 
const mrpt::math::TTwist2DgetVelocity () const
 
mrpt::math::TTwist2D getVelocityLocal () const
 
bool hadCollision () const
 
bool isInCollision () const
 
void resetCollisionFlag ()
 
void setName (const std::string &s)
 
void setPose (const mrpt::math::TPose3D &p) const
 
void setTwist (const mrpt::math::TTwist2D &dq) const
 

Static Public Member Functions

static Ptr factory (World *parent, const rapidxml::xml_node< char > *xml_node)
 
static Ptr factory (World *parent, const std::string &xml_text)
 
static void register_vehicle_class (const rapidxml::xml_node< char > *xml_node)
 

Static Public Attributes

static constexpr char DL_TIMESTAMP [] = "timestamp"
 
static constexpr char LOGGER_POSE [] = "logger_pose"
 
static constexpr char LOGGER_WHEEL [] = "logger_wheel"
 
static constexpr char PL_DQ_X [] = "dQx"
 
static constexpr char PL_DQ_Y [] = "dQy"
 
static constexpr char PL_DQ_Z [] = "dQz"
 
static constexpr char PL_Q_PITCH [] = "Qpitch"
 
static constexpr char PL_Q_ROLL [] = "Qroll"
 
static constexpr char PL_Q_X [] = "Qx"
 
static constexpr char PL_Q_Y [] = "Qy"
 
static constexpr char PL_Q_YAW [] = "Qyaw"
 
static constexpr char PL_Q_Z [] = "Qz"
 
static constexpr char WL_FRIC_X [] = "friction_x"
 
static constexpr char WL_FRIC_Y [] = "friction_y"
 
static constexpr char WL_TORQUE [] = "torque"
 
static constexpr char WL_VEL_X [] = "velocity_x"
 
static constexpr char WL_VEL_Y [] = "velocity_y"
 
static constexpr char WL_WEIGHT [] = "weight"
 

Protected Member Functions

virtual void dynamics_load_params_from_xml (const rapidxml::xml_node< char > *xml_node)=0
 
virtual void initLoggers ()
 
virtual mrpt::poses::CPose3D internalGuiGetVisualPose () override
 
virtual void internalGuiUpdate (mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override
 
virtual void invoke_motor_controllers (const TSimulContext &context, std::vector< double > &out_force_per_wheel)=0
 
void updateMaxRadiusFromPoly ()
 excludes the mass of wheels) More...
 
 VehicleBase (World *parent, size_t nWheels)
 
virtual void writeLogStrings ()
 
- Protected Member Functions inherited from mvsim::VisualObject
bool parseVisual (const rapidxml::xml_node< char > *visual_node)
 

Protected Attributes

mrpt::img::TColor m_chassis_color
 
mrpt::math::TPoint2D m_chassis_com
 
double m_chassis_mass
 
mrpt::math::TPolygon2D m_chassis_poly
 
double m_chassis_z_max
 
double m_chassis_z_min
 each change via updateMaxRadiusFromPoly() More...
 
b2Fixturem_fixture_chassis
 Created at. More...
 
std::vector< b2Fixture * > m_fixture_wheels
 
FrictionBasePtr m_friction
 
std::string m_log_path
 
std::map< std::string, std::shared_ptr< CSVLogger > > m_loggers
 
double m_max_radius
 
TListSensors m_sensors
 Sensors aboard. More...
 
std::vector< double > m_torque_per_wheel
 
size_t m_vehicle_index
 
std::vector< Wheelm_wheels_info
 
- Protected Attributes inherited from mvsim::VisualObject
std::shared_ptr< mrpt::opengl::CSetOfObjectsm_glBoundingBox
 
std::shared_ptr< mrpt::opengl::CSetOfObjectsm_glCustomVisual
 
int32_t m_glCustomVisualId = -1
 
Worldm_world
 
- Protected Attributes inherited from mvsim::Simulable
std::string m_name
 

Private Member Functions

void internal_internalGuiUpdate_forces (mrpt::opengl::COpenGLScene &scene)
 
void internal_internalGuiUpdate_sensors (mrpt::opengl::COpenGLScene &scene)
 

Private Attributes

std::vector< mrpt::math::TSegment3Dm_force_segments_for_rendering
 
std::mutex m_force_segments_for_rendering_cs
 
mrpt::opengl::CSetOfObjects::Ptr m_gl_chassis
 
mrpt::opengl::CSetOfLines::Ptr m_gl_forces
 
std::vector< mrpt::opengl::CSetOfObjects::Ptr > m_gl_wheels
 
std::mutex m_gui_mtx
 

Detailed Description

Virtual base class for each vehicle "actor" in the simulation. Derived classes implements different dynamical models (Differential, Ackermann,...)

Definition at line 41 of file VehicleBase.h.

Member Typedef Documentation

using mvsim::VehicleBase::Ptr = std::shared_ptr<VehicleBase>

Definition at line 44 of file VehicleBase.h.

Definition at line 102 of file VehicleBase.h.

Constructor & Destructor Documentation

VehicleBase::VehicleBase ( World parent,
size_t  nWheels 
)
protected

Definition at line 78 of file VehicleBase.cpp.

Member Function Documentation

void VehicleBase::apply_force ( const mrpt::math::TVector2D &  force,
const mrpt::math::TPoint2D applyPoint = mrpt::math::TPoint2D(0, 0) 
)
overridevirtual

Override to register external forces exerted by other WorldElements. Force is (fx,fy) in global coordinates. Application point is (local_ptx,local_pty) in the body local frame

Reimplemented from mvsim::Simulable.

Definition at line 763 of file VehicleBase.cpp.

void mvsim::VehicleBase::clearLogs ( )
inline

Definition at line 126 of file VehicleBase.h.

void VehicleBase::create_multibody_system ( b2World world)
virtual

Create bodies, fixtures, etc. for the dynamical simulation. May be overrided by derived classes

Create bodies, fixtures, etc. for the dynamical simulation

Definition at line 577 of file VehicleBase.cpp.

virtual void mvsim::VehicleBase::dynamics_load_params_from_xml ( const rapidxml::xml_node< char > *  xml_node)
protectedpure virtual

Parse node <dynamics>: The derived-class part of load_params_from_xml(), also called in factory(). Includes parsing the <controller></controller> block.

Implemented in mvsim::DynamicsAckermannDrivetrain, mvsim::DynamicsAckermann, and mvsim::DynamicsDifferential.

VehicleBase::Ptr VehicleBase::factory ( World parent,
const rapidxml::xml_node< char > *  root 
)
static

Class factory: Creates a vehicle from XML description of type "<vehicle>...</vehicle>".

Definition at line 124 of file VehicleBase.cpp.

VehicleBase::Ptr VehicleBase::factory ( World parent,
const std::string xml_text 
)
static

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 339 of file VehicleBase.cpp.

b2Fixture* mvsim::VehicleBase::get_fixture_chassis ( )
inline

Definition at line 139 of file VehicleBase.h.

const b2Fixture* mvsim::VehicleBase::get_fixture_chassis ( ) const
inline

Definition at line 141 of file VehicleBase.h.

std::vector<b2Fixture*>& mvsim::VehicleBase::get_fixture_wheels ( )
inline

Definition at line 140 of file VehicleBase.h.

const std::vector<b2Fixture*>& mvsim::VehicleBase::get_fixture_wheels ( ) const
inline

Definition at line 142 of file VehicleBase.h.

b2Body* mvsim::VehicleBase::getBox2DChassisBody ( )
inline

Definition at line 77 of file VehicleBase.h.

mrpt::math::TPoint2D mvsim::VehicleBase::getChassisCenterOfMass ( ) const
inline

In local coordinates (this excludes the mass of wheels)

Definition at line 78 of file VehicleBase.h.

virtual double mvsim::VehicleBase::getChassisMass ( ) const
inlinevirtual

Get the overall vehicle mass, excluding wheels.

Definition at line 76 of file VehicleBase.h.

const mrpt::math::TPolygon2D& mvsim::VehicleBase::getChassisShape ( ) const
inline

Get the 2D shape of the vehicle chassis, as set from the config file (only used for collision detection)

Definition at line 113 of file VehicleBase.h.

virtual ControllerBaseInterface* mvsim::VehicleBase::getControllerInterface ( )
pure virtual
std::shared_ptr<CSVLogger> mvsim::VehicleBase::getLoggerPtr ( std::string  logger_name)
inline

Definition at line 106 of file VehicleBase.h.

virtual float mvsim::VehicleBase::getMaxVehicleRadius ( ) const
inlinevirtual

Get (an approximation of) the max radius of the vehicle, from its point of reference (in meters)

Definition at line 74 of file VehicleBase.h.

size_t mvsim::VehicleBase::getNumWheels ( ) const
inline

Definition at line 83 of file VehicleBase.h.

const TListSensors& mvsim::VehicleBase::getSensors ( ) const
inline

Definition at line 104 of file VehicleBase.h.

TListSensors& mvsim::VehicleBase::getSensors ( )
inline

Definition at line 105 of file VehicleBase.h.

size_t mvsim::VehicleBase::getVehicleIndex ( ) const
inline

Get the vehicle index in the World

Definition at line 121 of file VehicleBase.h.

virtual mrpt::math::TTwist2D mvsim::VehicleBase::getVelocityLocalOdoEstimate ( ) const
pure virtual

Gets the current estimation of odometry-based velocity as reconstructed solely from wheels spinning velocities and geometry. This is the input of any realistic low-level controller onboard.

See also
getVelocityLocal()

Implemented in mvsim::DynamicsAckermannDrivetrain, mvsim::DynamicsAckermann, and mvsim::DynamicsDifferential.

const Wheel& mvsim::VehicleBase::getWheelInfo ( const size_t  idx) const
inline

Definition at line 84 of file VehicleBase.h.

Wheel& mvsim::VehicleBase::getWheelInfo ( const size_t  idx)
inline

Definition at line 88 of file VehicleBase.h.

void VehicleBase::getWheelsVelocityLocal ( std::vector< mrpt::math::TPoint2D > &  vels,
const mrpt::math::TTwist2D veh_vel_local 
) const

Current velocity of each wheel's center point (in local coords). Call with veh_vel_local=getVelocityLocal() for ground-truth.

Last time-step velocity of each wheel's center point (in local coords)

Definition at line 515 of file VehicleBase.cpp.

void VehicleBase::initLoggers ( )
protectedvirtual

Definition at line 714 of file VehicleBase.cpp.

void VehicleBase::internal_internalGuiUpdate_forces ( mrpt::opengl::COpenGLScene scene)
private

Definition at line 548 of file VehicleBase.cpp.

void VehicleBase::internal_internalGuiUpdate_sensors ( mrpt::opengl::COpenGLScene scene)
private

(depending on derived class). Size set at constructor.

Definition at line 542 of file VehicleBase.cpp.

mrpt::poses::CPose3D VehicleBase::internalGuiGetVisualPose ( )
overrideprotectedvirtual

Reimplemented from mvsim::VisualObject.

Definition at line 537 of file VehicleBase.cpp.

void VehicleBase::internalGuiUpdate ( mrpt::opengl::COpenGLScene scene,
bool  childrenOnly 
)
overrideprotectedvirtual

Implements mvsim::VisualObject.

Definition at line 654 of file VehicleBase.cpp.

virtual void mvsim::VehicleBase::invoke_motor_controllers ( const TSimulContext context,
std::vector< double > &  out_force_per_wheel 
)
protectedpure virtual
void mvsim::VehicleBase::newLogSession ( )
inline

Definition at line 130 of file VehicleBase.h.

void mvsim::VehicleBase::poses_mutex_lock ( )
inlineoverridevirtual

Implements mvsim::Simulable.

Definition at line 57 of file VehicleBase.h.

void mvsim::VehicleBase::poses_mutex_unlock ( )
inlineoverridevirtual

Implements mvsim::Simulable.

Definition at line 58 of file VehicleBase.h.

void VehicleBase::register_vehicle_class ( const rapidxml::xml_node< char > *  xml_node)
static

Register a new class of vehicles from XML description of type "<vehicle:class name='name'>...</vehicle:class>".

Definition at line 101 of file VehicleBase.cpp.

void VehicleBase::registerOnServer ( mvsim::Client c)
overridevirtual

Reimplemented from mvsim::Simulable.

Definition at line 772 of file VehicleBase.cpp.

void mvsim::VehicleBase::setRecording ( bool  record)
inline

Definition at line 122 of file VehicleBase.h.

void mvsim::VehicleBase::setVehicleIndex ( size_t  idx)
inline

Set the vehicle index in the World

Definition at line 119 of file VehicleBase.h.

void VehicleBase::simul_post_timestep ( const TSimulContext context)
overridevirtual

Override to do any required process right after the integration of dynamic equations for each timestep

Reimplemented from mvsim::Simulable.

Definition at line 468 of file VehicleBase.cpp.

void VehicleBase::simul_pre_timestep ( const TSimulContext context)
overridevirtual

Process right before the integration of dynamic equations for each timestep: set action forces from motors, update friction models, etc.

Reimplemented from mvsim::Simulable.

Definition at line 363 of file VehicleBase.cpp.

void VehicleBase::updateMaxRadiusFromPoly ( )
protected

excludes the mass of wheels)

Definition at line 564 of file VehicleBase.cpp.

void VehicleBase::writeLogStrings ( )
protectedvirtual

Definition at line 754 of file VehicleBase.cpp.

Member Data Documentation

constexpr char VehicleBase::DL_TIMESTAMP = "timestamp"
static

Definition at line 223 of file VehicleBase.h.

constexpr char VehicleBase::LOGGER_POSE = "logger_pose"
static

Definition at line 224 of file VehicleBase.h.

constexpr char VehicleBase::LOGGER_WHEEL = "logger_wheel"
static

Definition at line 225 of file VehicleBase.h.

mrpt::img::TColor mvsim::VehicleBase::m_chassis_color
protected

Definition at line 189 of file VehicleBase.h.

mrpt::math::TPoint2D mvsim::VehicleBase::m_chassis_com
protected

In local coordinates (this

Definition at line 191 of file VehicleBase.h.

double mvsim::VehicleBase::m_chassis_mass
protected

Definition at line 184 of file VehicleBase.h.

mrpt::math::TPolygon2D mvsim::VehicleBase::m_chassis_poly
protected

Definition at line 185 of file VehicleBase.h.

double mvsim::VehicleBase::m_chassis_z_max
protected

Definition at line 188 of file VehicleBase.h.

double mvsim::VehicleBase::m_chassis_z_min
protected

each change via updateMaxRadiusFromPoly()

Definition at line 188 of file VehicleBase.h.

b2Fixture* mvsim::VehicleBase::m_fixture_chassis
protected

Created at.

upon construction. Derived classes must define the order of the wheels, e.g. [0]=rear left, etc.

Definition at line 203 of file VehicleBase.h.

std::vector<b2Fixture*> mvsim::VehicleBase::m_fixture_wheels
protected

[0]:rear-left, etc.

Definition at line 204 of file VehicleBase.h.

std::vector<mrpt::math::TSegment3D> mvsim::VehicleBase::m_force_segments_for_rendering
private

Definition at line 218 of file VehicleBase.h.

std::mutex mvsim::VehicleBase::m_force_segments_for_rendering_cs
private

Definition at line 217 of file VehicleBase.h.

FrictionBasePtr mvsim::VehicleBase::m_friction
protected

Instance of friction model for the vehicle-to-ground interaction.

Definition at line 176 of file VehicleBase.h.

mrpt::opengl::CSetOfObjects::Ptr mvsim::VehicleBase::m_gl_chassis
private

Definition at line 214 of file VehicleBase.h.

mrpt::opengl::CSetOfLines::Ptr mvsim::VehicleBase::m_gl_forces
private

Definition at line 216 of file VehicleBase.h.

std::vector<mrpt::opengl::CSetOfObjects::Ptr> mvsim::VehicleBase::m_gl_wheels
private

Definition at line 215 of file VehicleBase.h.

std::mutex mvsim::VehicleBase::m_gui_mtx
private

Definition at line 220 of file VehicleBase.h.

std::string mvsim::VehicleBase::m_log_path
protected

Definition at line 149 of file VehicleBase.h.

std::map<std::string, std::shared_ptr<CSVLogger> > mvsim::VehicleBase::m_loggers
protected

Definition at line 148 of file VehicleBase.h.

double mvsim::VehicleBase::m_max_radius
protected

Automatically computed from m_chassis_poly upon

Definition at line 186 of file VehicleBase.h.

TListSensors mvsim::VehicleBase::m_sensors
protected

Sensors aboard.

Definition at line 178 of file VehicleBase.h.

std::vector<double> mvsim::VehicleBase::m_torque_per_wheel
protected

Updated in simul_pre_timestep()

Definition at line 181 of file VehicleBase.h.

size_t mvsim::VehicleBase::m_vehicle_index
protected

user-supplied index number: must be set/get'ed with setVehicleIndex() getVehicleIndex() (default=0)

Definition at line 173 of file VehicleBase.h.

std::vector<Wheel> mvsim::VehicleBase::m_wheels_info
protected

The fixed size of this vector is set

Definition at line 197 of file VehicleBase.h.

constexpr char VehicleBase::PL_DQ_X = "dQx"
static

Definition at line 233 of file VehicleBase.h.

constexpr char VehicleBase::PL_DQ_Y = "dQy"
static

Definition at line 234 of file VehicleBase.h.

constexpr char VehicleBase::PL_DQ_Z = "dQz"
static

Definition at line 235 of file VehicleBase.h.

constexpr char VehicleBase::PL_Q_PITCH = "Qpitch"
static

Definition at line 231 of file VehicleBase.h.

constexpr char VehicleBase::PL_Q_ROLL = "Qroll"
static

Definition at line 232 of file VehicleBase.h.

constexpr char VehicleBase::PL_Q_X = "Qx"
static

Definition at line 227 of file VehicleBase.h.

constexpr char VehicleBase::PL_Q_Y = "Qy"
static

Definition at line 228 of file VehicleBase.h.

constexpr char VehicleBase::PL_Q_YAW = "Qyaw"
static

Definition at line 230 of file VehicleBase.h.

constexpr char VehicleBase::PL_Q_Z = "Qz"
static

Definition at line 229 of file VehicleBase.h.

constexpr char VehicleBase::WL_FRIC_X = "friction_x"
static

Definition at line 241 of file VehicleBase.h.

constexpr char VehicleBase::WL_FRIC_Y = "friction_y"
static

Definition at line 242 of file VehicleBase.h.

constexpr char VehicleBase::WL_TORQUE = "torque"
static

Definition at line 237 of file VehicleBase.h.

constexpr char VehicleBase::WL_VEL_X = "velocity_x"
static

Definition at line 239 of file VehicleBase.h.

constexpr char VehicleBase::WL_VEL_Y = "velocity_y"
static

Definition at line 240 of file VehicleBase.h.

constexpr char VehicleBase::WL_WEIGHT = "weight"
static

Definition at line 238 of file VehicleBase.h.


The documentation for this class was generated from the following files:


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