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 >
 
- 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 chassisAndWheelsVisible (bool visible)
 
void clearLogs ()
 
virtual void create_multibody_system (b2World &world)
 
void freeOpenGLResources () override
 
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::TPolygon2D & getChassisShape () 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)
 
std::vector< mrpt::math::TVector2D > getWheelsVelocityLocal (const mrpt::math::TTwist2D &veh_vel_local) const
 
void newLogSession ()
 
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
const std::optional< Shape2p5 > & collisionShape () const
 
void customVisualVisible (const bool visible)
 
bool customVisualVisible () const
 
virtual void guiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical)
 
Worldparent ()
 
const Worldparent () const
 
void showCollisionShape (bool show)
 
 VisualObject (World *parent, bool insertCustomVizIntoViz=true, bool insertCustomVizIntoPhysical=true)
 
virtual ~VisualObject ()
 
- Public Member Functions inherited from mvsim::Simulable
const b2Bodyb2d_body () const
 
b2Bodyb2d_body ()
 
mrpt::poses::CPose2D getCPose2D () const
 Alternative to getPose() More...
 
mrpt::poses::CPose3D getCPose3D () const
 Alternative to getPose() More...
 
mrpt::math::TVector3D getLinearAcceleration () const
 
const std::string & getName () const
 
mrpt::math::TPose3D getPose () const
 
mrpt::math::TPose3D getPoseNoLock () const
 No thread-safe version. Used internally only. More...
 
WorldgetSimulableWorldObject ()
 
const WorldgetSimulableWorldObject () const
 
mrpt::math::TTwist2D getTwist () 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
 
 Simulable (World *parent)
 

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 Member Functions inherited from mvsim::VisualObject
static void FreeOpenGLResources ()
 

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"
 
- Static Public Attributes inherited from mvsim::VisualObject
static double GeometryEpsilon = 1e-3
 

Protected Member Functions

virtual void dynamics_load_params_from_xml (const rapidxml::xml_node< char > *xml_node)=0
 
virtual void initLoggers ()
 
virtual void internalGuiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
 
virtual std::vector< double > invoke_motor_controllers (const TSimulContext &context)=0
 
virtual void invoke_motor_controllers_post_step ([[maybe_unused]] const TSimulContext &context)
 
VisualObjectmeAsVisualObject () override
 
void updateMaxRadiusFromPoly ()
 
 VehicleBase (World *parent, size_t nWheels)
 
virtual void writeLogStrings ()
 
- Protected Member Functions inherited from mvsim::VisualObject
void addCustomVisualization (const mrpt::opengl::CRenderizable::Ptr &glModel, const mrpt::poses::CPose3D &modelPose={}, const float modelScale=1.0f, const std::string &modelName="group", const std::optional< std::string > &modelURI=std::nullopt, const bool initialShowBoundingBox=false)
 
bool parseVisual (const rapidxml::xml_node< char > &rootNode)
 Returns true if there is at least one <visual>...</visual> entry. More...
 
bool parseVisual (const JointXMLnode<> &rootNode)
 
void setCollisionShape (const Shape2p5 &cs)
 

Protected Attributes

mrpt::img::TColor chassis_color_ {0xff, 0x00, 0x00}
 
mrpt::math::TPoint2D chassis_com_ {0, 0}
 
double chassis_mass_ = 15.0
 
mrpt::math::TPolygon2D chassis_poly_
 
double chassis_z_max_ = 0.6
 
double chassis_z_min_ = 0.05
 
b2Fixturefixture_chassis_
 Created at. More...
 
std::vector< b2Fixture * > fixture_wheels_
 
FrictionBasePtr friction_
 
std::string log_path_
 
std::map< std::string, std::shared_ptr< CSVLogger > > loggers_
 
double maxRadius_ = 0.1
 
TListSensors sensors_
 Sensors aboard. More...
 
size_t vehicle_index_ = 0
 
std::deque< Wheelwheels_info_
 
- Protected Attributes inherited from mvsim::VisualObject
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCollision_
 
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCustomVisual_
 
int32_t glCustomVisualId_ = -1
 
const bool insertCustomVizIntoPhysical_ = true
 
const bool insertCustomVizIntoViz_ = true
 
Worldworld_
 
- Protected Attributes inherited from mvsim::Simulable
std::string name_
 

Private Member Functions

void internal_internalGuiUpdate_forces (mrpt::opengl::COpenGLScene &scene)
 
void internal_internalGuiUpdate_sensors (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical)
 

Private Attributes

std::vector< mrpt::math::TSegment3D > forceSegmentsForRendering_
 
std::mutex forceSegmentsForRenderingMtx_
 
mrpt::opengl::CSetOfObjects::Ptr glChassis_
 
mrpt::opengl::CSetOfLines::Ptr glForces_
 
mrpt::opengl::CSetOfLines::Ptr glMotorTorques_
 
std::vector< mrpt::opengl::CSetOfObjects::Ptr > glWheels_
 
std::vector< mrpt::math::TSegment3D > torqueSegmentsForRendering_
 

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

◆ Ptr

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

Definition at line 44 of file VehicleBase.h.

Constructor & Destructor Documentation

◆ VehicleBase()

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

Definition at line 84 of file VehicleBase.cpp.

Member Function Documentation

◆ apply_force()

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 839 of file VehicleBase.cpp.

◆ chassisAndWheelsVisible()

void VehicleBase::chassisAndWheelsVisible ( bool  visible)

Definition at line 855 of file VehicleBase.cpp.

◆ clearLogs()

void mvsim::VehicleBase::clearLogs ( )
inline

Definition at line 120 of file VehicleBase.h.

◆ create_multibody_system()

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 615 of file VehicleBase.cpp.

◆ dynamics_load_params_from_xml()

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::DynamicsDifferential, mvsim::DynamicsAckermannDrivetrain, and mvsim::DynamicsAckermann.

◆ factory() [1/2]

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 125 of file VehicleBase.cpp.

◆ factory() [2/2]

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 365 of file VehicleBase.cpp.

◆ freeOpenGLResources()

void mvsim::VehicleBase::freeOpenGLResources ( )
inlineoverridevirtual

Reimplemented from mvsim::Simulable.

Definition at line 141 of file VehicleBase.h.

◆ get_fixture_chassis() [1/2]

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

Definition at line 133 of file VehicleBase.h.

◆ get_fixture_chassis() [2/2]

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

Definition at line 135 of file VehicleBase.h.

◆ get_fixture_wheels() [1/2]

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

Definition at line 134 of file VehicleBase.h.

◆ get_fixture_wheels() [2/2]

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

Definition at line 136 of file VehicleBase.h.

◆ getBox2DChassisBody()

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

Definition at line 74 of file VehicleBase.h.

◆ getChassisCenterOfMass()

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

In local coordinates (this excludes the mass of wheels)

Definition at line 75 of file VehicleBase.h.

◆ getChassisMass()

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

Get the overall vehicle mass, excluding wheels.

Definition at line 73 of file VehicleBase.h.

◆ getChassisShape()

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 107 of file VehicleBase.h.

◆ getControllerInterface()

virtual ControllerBaseInterface* mvsim::VehicleBase::getControllerInterface ( )
pure virtual

◆ getLoggerPtr()

std::shared_ptr<CSVLogger> mvsim::VehicleBase::getLoggerPtr ( std::string  logger_name)
inline

Definition at line 100 of file VehicleBase.h.

◆ getMaxVehicleRadius()

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 71 of file VehicleBase.h.

◆ getNumWheels()

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

Definition at line 80 of file VehicleBase.h.

◆ getSensors() [1/2]

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

Definition at line 98 of file VehicleBase.h.

◆ getSensors() [2/2]

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

Definition at line 99 of file VehicleBase.h.

◆ getVehicleIndex()

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

Get the vehicle index in the World

Definition at line 115 of file VehicleBase.h.

◆ getVelocityLocalOdoEstimate()

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::DynamicsDifferential, mvsim::DynamicsAckermannDrivetrain, and mvsim::DynamicsAckermann.

◆ getWheelInfo() [1/2]

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

Definition at line 81 of file VehicleBase.h.

◆ getWheelInfo() [2/2]

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

Definition at line 85 of file VehicleBase.h.

◆ getWheelsVelocityLocal()

std::vector< mrpt::math::TVector2D > VehicleBase::getWheelsVelocityLocal ( 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 551 of file VehicleBase.cpp.

◆ initLoggers()

void VehicleBase::initLoggers ( )
protectedvirtual

Definition at line 790 of file VehicleBase.cpp.

◆ internal_internalGuiUpdate_forces()

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

Definition at line 581 of file VehicleBase.cpp.

◆ internal_internalGuiUpdate_sensors()

void VehicleBase::internal_internalGuiUpdate_sensors ( const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &  viz,
const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &  physical 
)
private

Definition at line 574 of file VehicleBase.cpp.

◆ internalGuiUpdate()

void VehicleBase::internalGuiUpdate ( const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &  viz,
const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &  physical,
bool  childrenOnly 
)
overrideprotectedvirtual

Implements mvsim::VisualObject.

Definition at line 693 of file VehicleBase.cpp.

◆ invoke_motor_controllers()

virtual std::vector<double> mvsim::VehicleBase::invoke_motor_controllers ( const TSimulContext context)
protectedpure virtual

◆ invoke_motor_controllers_post_step()

virtual void mvsim::VehicleBase::invoke_motor_controllers_post_step ( [[maybe_unused] ] const TSimulContext context)
inlineprotectedvirtual

Definition at line 171 of file VehicleBase.h.

◆ meAsVisualObject()

VisualObject* mvsim::VehicleBase::meAsVisualObject ( )
inlineoverrideprotectedvirtual

Reimplemented from mvsim::Simulable.

Definition at line 176 of file VehicleBase.h.

◆ newLogSession()

void mvsim::VehicleBase::newLogSession ( )
inline

Definition at line 124 of file VehicleBase.h.

◆ register_vehicle_class()

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 102 of file VehicleBase.cpp.

◆ registerOnServer()

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

Reimplemented from mvsim::Simulable.

Definition at line 848 of file VehicleBase.cpp.

◆ setRecording()

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

Definition at line 116 of file VehicleBase.h.

◆ setVehicleIndex()

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

Set the vehicle index in the World

Definition at line 113 of file VehicleBase.h.

◆ simul_post_timestep()

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 502 of file VehicleBase.cpp.

◆ simul_pre_timestep()

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 389 of file VehicleBase.cpp.

◆ updateMaxRadiusFromPoly()

void VehicleBase::updateMaxRadiusFromPoly ( )
protected

Definition at line 602 of file VehicleBase.cpp.

◆ writeLogStrings()

void VehicleBase::writeLogStrings ( )
protectedvirtual

Definition at line 830 of file VehicleBase.cpp.

Member Data Documentation

◆ chassis_color_

mrpt::img::TColor mvsim::VehicleBase::chassis_color_ {0xff, 0x00, 0x00}
protected

Definition at line 197 of file VehicleBase.h.

◆ chassis_com_

mrpt::math::TPoint2D mvsim::VehicleBase::chassis_com_ {0, 0}
protected

center of mass. in local coordinates (this excludes the mass of wheels)

Definition at line 201 of file VehicleBase.h.

◆ chassis_mass_

double mvsim::VehicleBase::chassis_mass_ = 15.0
protected

Definition at line 188 of file VehicleBase.h.

◆ chassis_poly_

mrpt::math::TPolygon2D mvsim::VehicleBase::chassis_poly_
protected

Definition at line 189 of file VehicleBase.h.

◆ chassis_z_max_

double mvsim::VehicleBase::chassis_z_max_ = 0.6
protected

Definition at line 195 of file VehicleBase.h.

◆ chassis_z_min_

double mvsim::VehicleBase::chassis_z_min_ = 0.05
protected

Definition at line 195 of file VehicleBase.h.

◆ DL_TIMESTAMP

constexpr char VehicleBase::DL_TIMESTAMP = "timestamp"
static

Definition at line 236 of file VehicleBase.h.

◆ fixture_chassis_

b2Fixture* mvsim::VehicleBase::fixture_chassis_
protected

Created at.

Definition at line 212 of file VehicleBase.h.

◆ fixture_wheels_

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

[0]:rear-left, etc. (depending on derived class). Size set at constructor.

Definition at line 216 of file VehicleBase.h.

◆ forceSegmentsForRendering_

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

Definition at line 231 of file VehicleBase.h.

◆ forceSegmentsForRenderingMtx_

std::mutex mvsim::VehicleBase::forceSegmentsForRenderingMtx_
private

Definition at line 233 of file VehicleBase.h.

◆ friction_

FrictionBasePtr mvsim::VehicleBase::friction_
protected

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

Definition at line 183 of file VehicleBase.h.

◆ glChassis_

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

Definition at line 226 of file VehicleBase.h.

◆ glForces_

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

Definition at line 228 of file VehicleBase.h.

◆ glMotorTorques_

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

Definition at line 229 of file VehicleBase.h.

◆ glWheels_

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

Definition at line 227 of file VehicleBase.h.

◆ log_path_

std::string mvsim::VehicleBase::log_path_
protected

Definition at line 149 of file VehicleBase.h.

◆ LOGGER_POSE

constexpr char VehicleBase::LOGGER_POSE = "logger_pose"
static

Definition at line 237 of file VehicleBase.h.

◆ LOGGER_WHEEL

constexpr char VehicleBase::LOGGER_WHEEL = "logger_wheel"
static

Definition at line 238 of file VehicleBase.h.

◆ loggers_

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

Definition at line 148 of file VehicleBase.h.

◆ maxRadius_

double mvsim::VehicleBase::maxRadius_ = 0.1
protected

Automatically computed from chassis_poly_ upon each change via updateMaxRadiusFromPoly()

Definition at line 193 of file VehicleBase.h.

◆ PL_DQ_X

constexpr char VehicleBase::PL_DQ_X = "dQx"
static

Definition at line 246 of file VehicleBase.h.

◆ PL_DQ_Y

constexpr char VehicleBase::PL_DQ_Y = "dQy"
static

Definition at line 247 of file VehicleBase.h.

◆ PL_DQ_Z

constexpr char VehicleBase::PL_DQ_Z = "dQz"
static

Definition at line 248 of file VehicleBase.h.

◆ PL_Q_PITCH

constexpr char VehicleBase::PL_Q_PITCH = "Qpitch"
static

Definition at line 244 of file VehicleBase.h.

◆ PL_Q_ROLL

constexpr char VehicleBase::PL_Q_ROLL = "Qroll"
static

Definition at line 245 of file VehicleBase.h.

◆ PL_Q_X

constexpr char VehicleBase::PL_Q_X = "Qx"
static

Definition at line 240 of file VehicleBase.h.

◆ PL_Q_Y

constexpr char VehicleBase::PL_Q_Y = "Qy"
static

Definition at line 241 of file VehicleBase.h.

◆ PL_Q_YAW

constexpr char VehicleBase::PL_Q_YAW = "Qyaw"
static

Definition at line 243 of file VehicleBase.h.

◆ PL_Q_Z

constexpr char VehicleBase::PL_Q_Z = "Qz"
static

Definition at line 242 of file VehicleBase.h.

◆ sensors_

TListSensors mvsim::VehicleBase::sensors_
protected

Sensors aboard.

Definition at line 185 of file VehicleBase.h.

◆ torqueSegmentsForRendering_

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

Definition at line 232 of file VehicleBase.h.

◆ vehicle_index_

size_t mvsim::VehicleBase::vehicle_index_ = 0
protected

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

Definition at line 180 of file VehicleBase.h.

◆ wheels_info_

std::deque<Wheel> mvsim::VehicleBase::wheels_info_
protected

Wheels info. The fixed size of this vector is set upon construction. Derived classes must define the order of the wheels, e.g. [0]=rear left, etc.

Definition at line 209 of file VehicleBase.h.

◆ WL_FRIC_X

constexpr char VehicleBase::WL_FRIC_X = "friction_x"
static

Definition at line 254 of file VehicleBase.h.

◆ WL_FRIC_Y

constexpr char VehicleBase::WL_FRIC_Y = "friction_y"
static

Definition at line 255 of file VehicleBase.h.

◆ WL_TORQUE

constexpr char VehicleBase::WL_TORQUE = "torque"
static

Definition at line 250 of file VehicleBase.h.

◆ WL_VEL_X

constexpr char VehicleBase::WL_VEL_X = "velocity_x"
static

Definition at line 252 of file VehicleBase.h.

◆ WL_VEL_Y

constexpr char VehicleBase::WL_VEL_Y = "velocity_y"
static

Definition at line 253 of file VehicleBase.h.

◆ WL_WEIGHT

constexpr char VehicleBase::WL_WEIGHT = "weight"
static

Definition at line 251 of file VehicleBase.h.


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


mvsim
Author(s):
autogenerated on Tue Jul 4 2023 03:08:23