#include <VehicleDifferential.h>

Classes | |
| struct | ConfigPerWheel |
| class | ControllerRawForces |
| class | ControllerTwistIdeal |
| class | ControllerTwistPID |
| struct | TControllerInput |
| struct | TControllerOutput |
Public Types | |
| enum | { WHEEL_L = 0, WHEEL_R = 1, WHEEL_CASTER_FRONT = 2, WHEEL_LR = 0, WHEEL_RR = 1, WHEEL_LF = 2, WHEEL_RF = 3 } |
Public Types inherited from mvsim::VehicleBase | |
| using | Ptr = std::shared_ptr< VehicleBase > |
Public Types inherited from mvsim::Simulable | |
| using | Ptr = std::shared_ptr< Simulable > |
Public Member Functions | |
| DynamicsDifferential (World *parent) | |
| DynamicsDifferential (World *parent, const std::vector< ConfigPerWheel > &cfgPerWheel) | |
| virtual mrpt::math::TTwist2D | getVelocityLocalOdoEstimate () const 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) |
| double | chassisZMax () const |
| double | chassisZMin () const |
| void | clearLogs () |
| virtual void | create_multibody_system (b2World &world) |
| void | freeOpenGLResources () override |
| b2Fixture * | get_fixture_chassis () |
| const b2Fixture * | get_fixture_chassis () const |
| std::vector< b2Fixture * > & | get_fixture_wheels () |
| const std::vector< b2Fixture * > & | get_fixture_wheels () const |
| b2Body * | getBox2DChassisBody () |
| virtual double | getChassisMass () const |
| const mrpt::math::TPolygon2D & | getChassisShape () const |
| std::shared_ptr< CSVLogger > | getLoggerPtr (std::string logger_name) |
| virtual float | getMaxVehicleRadius () const |
| size_t | getNumWheels () const |
| TListSensors & | getSensors () |
| const TListSensors & | getSensors () const |
| size_t | getVehicleIndex () const |
| Wheel & | getWheelInfo (const size_t idx) |
| const Wheel & | getWheelInfo (const size_t idx) const |
| std::vector< mrpt::math::TVector2D > | getWheelsVelocityLocal (const mrpt::math::TTwist2D &veh_vel_local) const |
| bool | isLogging () 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 |
| 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) |
| World * | parent () |
| const World * | parent () const |
| void | showCollisionShape (bool show) |
| VisualObject (World *parent, bool insertCustomVizIntoViz=true, bool insertCustomVizIntoPhysical=true) | |
| virtual | ~VisualObject () |
Public Member Functions inherited from mvsim::Simulable | |
| b2Body * | b2d_body () |
| const b2Body * | b2d_body () const |
| mrpt::poses::CPose2D | getCPose2D () const |
| Alternative to getPose() More... | |
| mrpt::poses::CPose3D | getCPose3D () const |
| Alternative to getPose() More... | |
| virtual std::optional< float > | getElevationAt ([[maybe_unused]] const mrpt::math::TPoint2D &worldXY) const |
| 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... | |
| virtual mrpt::math::TPose3D | getRelativePose () const |
| World * | getSimulableWorldObject () |
| const World * | getSimulableWorldObject () 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, bool notifyChange=true) const |
| virtual void | setRelativePose (const mrpt::math::TPose3D &p) |
| void | setTwist (const mrpt::math::TTwist2D &dq) const |
| Simulable (World *parent) | |
Protected Member Functions | |
| 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) |
| VisualObject * | meAsVisualObject () 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 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) |
Protected Attributes | |
| const std::vector< ConfigPerWheel > | configPerWheel_ |
| 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 |
| b2Fixture * | fixture_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< Wheel > | wheels_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 |
| World * | world_ |
Protected Attributes inherited from mvsim::Simulable | |
| std::string | name_ |
Private Attributes | |
| ControllerBase::Ptr | controller_ |
| The installed controller. More... | |
Controllers | |
| using | ControllerBase = ControllerBaseTempl< DynamicsDifferential > |
| const ControllerBase::Ptr & | getController () const |
| ControllerBase::Ptr & | getController () |
| virtual ControllerBaseInterface * | getControllerInterface () override |
Additional Inherited Members | |
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) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| static void | register_vehicle_class (const World &parent, 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 [] = "q4pitch" |
| static constexpr char | PL_Q_ROLL [] = "q5roll" |
| static constexpr char | PL_Q_X [] = "q0x" |
| static constexpr char | PL_Q_Y [] = "q1y" |
| static constexpr char | PL_Q_YAW [] = "q3yaw" |
| static constexpr char | PL_Q_Z [] = "q2z" |
| 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 |
Implementation of differential-driven vehicles with only two wheels. Simplified model for pure planar scenarios only, do not use with ramps. For that, use Differential or Ackermann models with 3 or 4 wheels.
Definition at line 30 of file VehicleDifferential.h.
Virtual base for controllers of vehicles of type DynamicsDifferential
Definition at line 88 of file VehicleDifferential.h.
| anonymous enum |
| Enumerator | |
|---|---|
| WHEEL_L | |
| WHEEL_R | |
| WHEEL_CASTER_FRONT | |
| WHEEL_LR | |
| WHEEL_RR | |
| WHEEL_LF | |
| WHEEL_RF | |
Definition at line 34 of file VehicleDifferential.h.
|
inline |
Definition at line 60 of file VehicleDifferential.h.
| DynamicsDifferential::DynamicsDifferential | ( | World * | parent, |
| const std::vector< ConfigPerWheel > & | cfgPerWheel | ||
| ) |
Definition at line 22 of file VehicleDifferential.cpp.
|
overrideprotectedvirtual |
The derived-class part of load_params_from_xml()
Implements mvsim::VehicleBase.
Definition at line 48 of file VehicleDifferential.cpp.
|
inline |
Definition at line 202 of file VehicleDifferential.h.
|
inline |
Definition at line 201 of file VehicleDifferential.h.
|
inlineoverridevirtual |
Implements mvsim::VehicleBase.
Definition at line 203 of file VehicleDifferential.h.
|
overridevirtual |
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.
Implements mvsim::VehicleBase.
Definition at line 173 of file VehicleDifferential.cpp.
|
overrideprotectedvirtual |
Implements mvsim::VehicleBase.
Definition at line 128 of file VehicleDifferential.cpp.
|
overrideprotectedvirtual |
Definition at line 167 of file VehicleDifferential.cpp.
|
protected |
Defined at ctor time:
Definition at line 217 of file VehicleDifferential.h.
|
private |
The installed controller.
Definition at line 220 of file VehicleDifferential.h.