Public Member Functions | List of all members
mvsim::DynamicsDifferential_4_wheels Class Reference

#include <VehicleDifferential.h>

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

Public Member Functions

 DynamicsDifferential_4_wheels (World *parent)
 
- Public Member Functions inherited from mvsim::DynamicsDifferential
 DynamicsDifferential (World *parent)
 
 DynamicsDifferential (World *parent, const std::vector< ConfigPerWheel > &cfgPerWheel)
 
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate () const override
 
const ControllerBase::PtrgetController () const
 
ControllerBase::PtrgetController ()
 
virtual ControllerBaseInterfacegetControllerInterface () override
 
- Public Member Functions inherited from mvsim::VehicleBase
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
 
std::shared_ptr< CSVLoggergetLoggerPtr (std::string logger_name)
 
virtual float getMaxVehicleRadius () const
 
size_t getNumWheels () const
 
const TListSensorsgetSensors () const
 
TListSensorsgetSensors ()
 
size_t getVehicleIndex () const
 
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)
 

Additional Inherited Members

- Public Types inherited from mvsim::DynamicsDifferential
enum  {
  WHEEL_L = 0, WHEEL_R = 1, WHEEL_CASTER_FRONT = 2, WHEEL_LR = 0,
  WHEEL_RR = 1, WHEEL_LF = 2, WHEEL_RF = 3
}
 
using ControllerBase = ControllerBaseTempl< DynamicsDifferential >
 
- Public Types inherited from mvsim::VehicleBase
using Ptr = std::shared_ptr< VehicleBase >
 
- Public Types inherited from mvsim::Simulable
using Ptr = std::shared_ptr< Simulable >
 
- Static Public Member Functions inherited from mvsim::VehicleBase
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 inherited from mvsim::VehicleBase
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 inherited from mvsim::DynamicsDifferential
virtual void dynamics_load_params_from_xml (const rapidxml::xml_node< char > *xml_node) override
 
virtual std::vector< double > invoke_motor_controllers (const TSimulContext &context) override
 
virtual void invoke_motor_controllers_post_step (const TSimulContext &context) override
 
- Protected Member Functions inherited from mvsim::VehicleBase
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 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 inherited from mvsim::DynamicsDifferential
const std::vector< ConfigPerWheelconfigPerWheel_
 Defined at ctor time: More...
 
- Protected Attributes inherited from mvsim::VehicleBase
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_
 

Detailed Description

Definition at line 238 of file VehicleDifferential.h.

Constructor & Destructor Documentation

◆ DynamicsDifferential_4_wheels()

mvsim::DynamicsDifferential_4_wheels::DynamicsDifferential_4_wheels ( World parent)
inline

Definition at line 243 of file VehicleDifferential.h.


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


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