Public Member Functions | Public Attributes | Protected Attributes | List of all members
mvsim::Wheel Class Reference

#include <Wheel.h>

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

Public Member Functions

std::string asString () const
 
void getAs3DObject (mrpt::opengl::CSetOfObjects &obj, bool isPhysicalScene)
 
void internalGuiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
 
void loadFromXML (const rapidxml::xml_node< char > *xml_node)
 
mrpt::math::TPose3D pose () const
 
void recalcInertia ()
 Recompute Iyy from mass, diameter and height. More...
 
 Wheel (World *world)
 
- Public Member Functions inherited from mvsim::VisualObject
const std::optional< Shape2p5 > & collisionShape () const
 
bool customVisualVisible () const
 
void customVisualVisible (const bool visible)
 
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 Attributes

mrpt::img::TColor color {0xff323232}
 
double diameter = .4
 
double Iyy = 1.0
 
std::string linked_yaw_object_name
 
double linked_yaw_offset = .0
 
double mass = 2.0
 [kg] More...
 
const TParameterDefinitions params_
 
double width = .2
 
double x = 0
 
double y = -0.5
 
double yaw = 0
 

Protected Attributes

double phi = 0
 
double w = 0
 
- 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_
 

Additional Inherited Members

- Static Public Member Functions inherited from mvsim::VisualObject
static void FreeOpenGLResources ()
 
- Static Public Attributes inherited from mvsim::VisualObject
static double GeometryEpsilon = 1e-3
 
- 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 JointXMLnode<> &rootNode)
 
bool parseVisual (const rapidxml::xml_node< char > &rootNode)
 Returns true if there is at least one <visual>...</visual> entry. More...
 
void setCollisionShape (const Shape2p5 &cs)
 

Detailed Description

Common info for 2D wheels, for usage in derived classes. Wheels are modeled as a mass with a cylindrical shape.

Definition at line 33 of file Wheel.h.

Constructor & Destructor Documentation

◆ Wheel()

Wheel::Wheel ( World world)

Definition at line 25 of file Wheel.cpp.

Member Function Documentation

◆ asString()

std::string Wheel::asString ( ) const

Generates a human-readable description of the wheel parameters and kinematic status

Definition at line 106 of file Wheel.cpp.

◆ getAs3DObject()

void Wheel::getAs3DObject ( mrpt::opengl::CSetOfObjects &  obj,
bool  isPhysicalScene 
)

Definition at line 27 of file Wheel.cpp.

◆ internalGuiUpdate()

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

Implements mvsim::VisualObject.

Definition at line 98 of file Wheel.cpp.

◆ loadFromXML()

void Wheel::loadFromXML ( const rapidxml::xml_node< char > *  xml_node)

Definition at line 62 of file Wheel.cpp.

◆ pose()

mrpt::math::TPose3D mvsim::Wheel::pose ( ) const
inline

Pose of the wheel wrt the chassis ref point (in local coords)

Definition at line 43 of file Wheel.h.

◆ recalcInertia()

void Wheel::recalcInertia ( )

Recompute Iyy from mass, diameter and height.

Definition at line 92 of file Wheel.cpp.

Member Data Documentation

◆ color

mrpt::img::TColor mvsim::Wheel::color {0xff323232}

Color for OpenGL rendering

Definition at line 54 of file Wheel.h.

◆ diameter

double mvsim::Wheel::diameter = .4

Length(diameter) and width of the wheel rectangle [m]

Definition at line 46 of file Wheel.h.

◆ Iyy

double mvsim::Wheel::Iyy = 1.0

Inertia: computed automatically from geometry at constructor and at loadFromXML(), but can be overrided.

Definition at line 51 of file Wheel.h.

◆ linked_yaw_object_name

std::string mvsim::Wheel::linked_yaw_object_name

Optional: name of a named custom visualization object in my parent vehicle, whose angle (yaw) is to be set whenever this wheel angle is updated.

Definition at line 60 of file Wheel.h.

◆ linked_yaw_offset

double mvsim::Wheel::linked_yaw_offset = .0

Definition at line 61 of file Wheel.h.

◆ mass

double mvsim::Wheel::mass = 2.0

[kg]

Definition at line 47 of file Wheel.h.

◆ params_

const TParameterDefinitions mvsim::Wheel::params_
Initial value:
= {
{"mass", {"%lf", &mass}},
{"width", {"%lf", &width}},
{"diameter", {"%lf", &diameter}},
{"color", {"%color", &color}},
{"inertia", {"%lf", &Iyy}},
{"linked_yaw", {"%s", &linked_yaw_object_name}},
{"linked_yaw_offset_deg", {"%lf_deg", &linked_yaw_offset}}}

Definition at line 63 of file Wheel.h.

◆ phi

double mvsim::Wheel::phi = 0
protected

Angular position and velocity of the wheel as it spins over its shaft (rad, rad/s)

Definition at line 93 of file Wheel.h.

◆ w

double mvsim::Wheel::w = 0
protected

Definition at line 93 of file Wheel.h.

◆ width

double mvsim::Wheel::width = .2

Definition at line 46 of file Wheel.h.

◆ x

double mvsim::Wheel::x = 0

Location of the wheel wrt the chassis ref point [m,rad] (in local coords)

Definition at line 40 of file Wheel.h.

◆ y

double mvsim::Wheel::y = -0.5

Definition at line 40 of file Wheel.h.

◆ yaw

double mvsim::Wheel::yaw = 0

Definition at line 40 of file Wheel.h.


The documentation for this class was generated from the following files:
mvsim::Wheel::linked_yaw_object_name
std::string linked_yaw_object_name
Definition: Wheel.h:60
mvsim::Wheel::diameter
double diameter
Definition: Wheel.h:46
mvsim::Wheel::Iyy
double Iyy
Definition: Wheel.h:51
mvsim::Wheel::color
mrpt::img::TColor color
Definition: Wheel.h:54
mvsim::Wheel::width
double width
Definition: Wheel.h:46
mvsim::Wheel::linked_yaw_offset
double linked_yaw_offset
Definition: Wheel.h:61
mvsim::Wheel::mass
double mass
[kg]
Definition: Wheel.h:47


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:10