#include <VerticalPlane.h>

Public Member Functions | |
| virtual void | loadConfigFrom (const rapidxml::xml_node< char > *root) override |
| void | simul_post_timestep (const TSimulContext &context) override |
| void | simul_pre_timestep (const TSimulContext &context) override |
| VerticalPlane (World *parent, const rapidxml::xml_node< char > *root) | |
| virtual | ~VerticalPlane () |
Public Member Functions inherited from mvsim::WorldElementBase | |
| WorldElementBase (World *parent) | |
| virtual | ~WorldElementBase () |
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 | |
| virtual void | apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) |
| b2Body * | b2d_body () |
| const b2Body * | b2d_body () const |
| virtual void | freeOpenGLResources () |
| 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 |
| virtual VisualObject * | meAsVisualObject () |
| virtual void | registerOnServer (mvsim::Client &c) |
| 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 | internalGuiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override |
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 | |
| b2Body * | b2dBody_ = nullptr |
| mrpt::img::TColor | color_ = {0xa0, 0xa0, 0xa0, 0xff} |
| std::string | cull_faces_ = "NONE" |
| bool | enableShadows_ = true |
| b2Fixture * | fixture_block_ = nullptr |
| mrpt::opengl::CTexturedPlane::Ptr | gl_plane_ |
| mrpt::opengl::CSetOfTexturedTriangles::Ptr | gl_plane_text_ |
| mrpt::opengl::CSetOfObjects::Ptr | glGroup_ |
| float | height_ = 3.0f |
| double | restitution_ = 0.01 |
| Default: 0.01. More... | |
| std::string | textureFileName_ |
| double | textureSizeX_ = 1.0 |
| double | textureSizeY_ = 1.0 |
| float | x0_ = -10 |
| float | x1_ = -10 |
| float | y0_ = -10 |
| float | y1_ = 10 |
| float | z_ = .0f |
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_ |
Additional Inherited Members | |
Public Types inherited from mvsim::WorldElementBase | |
| using | Ptr = std::shared_ptr< WorldElementBase > |
Public Types inherited from mvsim::Simulable | |
| using | Ptr = std::shared_ptr< Simulable > |
Static Public Member Functions inherited from mvsim::WorldElementBase | |
| static Ptr | factory (World *parent, const rapidxml::xml_node< char > *xml_node, const char *class_name=nullptr) |
Static Public Member Functions inherited from mvsim::VisualObject | |
| static void | FreeOpenGLResources () |
Static Public Attributes inherited from mvsim::VisualObject | |
| static double | GeometryEpsilon = 1e-3 |
A vertical plane, visible from one or both sides (see "cull_faces"), conveniently defined by starting and end points (x0,y0)-(x1,y1).
Definition at line 24 of file VerticalPlane.h.
| VerticalPlane::VerticalPlane | ( | World * | parent, |
| const rapidxml::xml_node< char > * | root | ||
| ) |
Definition at line 25 of file VerticalPlane.cpp.
|
virtual |
Definition at line 33 of file VerticalPlane.cpp.
|
overrideprotectedvirtual |
Implements mvsim::VisualObject.
Definition at line 118 of file VerticalPlane.cpp.
|
overridevirtual |
Implements mvsim::WorldElementBase.
Definition at line 35 of file VerticalPlane.cpp.
|
overridevirtual |
Override to do any required process right after the integration of dynamic equations for each timestep. IMPORTANT: Reimplementations MUST also call this base method, since it is in charge of important tasks (e.g. update q_, dq_)
Reimplemented from mvsim::Simulable.
Definition at line 251 of file VerticalPlane.cpp.
|
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 246 of file VerticalPlane.cpp.
|
protected |
Definition at line 57 of file VerticalPlane.h.
|
protected |
Definition at line 42 of file VerticalPlane.h.
|
protected |
Definition at line 51 of file VerticalPlane.h.
|
protected |
Definition at line 43 of file VerticalPlane.h.
|
protected |
Definition at line 59 of file VerticalPlane.h.
|
protected |
Definition at line 53 of file VerticalPlane.h.
|
protected |
Definition at line 54 of file VerticalPlane.h.
|
protected |
Definition at line 55 of file VerticalPlane.h.
|
protected |
Definition at line 50 of file VerticalPlane.h.
|
protected |
Default: 0.01.
Definition at line 58 of file VerticalPlane.h.
|
protected |
If defined, it overrides the plain color in color_
Definition at line 46 of file VerticalPlane.h.
|
protected |
Definition at line 47 of file VerticalPlane.h.
|
protected |
Definition at line 48 of file VerticalPlane.h.
|
protected |
Definition at line 41 of file VerticalPlane.h.
|
protected |
Definition at line 41 of file VerticalPlane.h.
|
protected |
Definition at line 41 of file VerticalPlane.h.
|
protected |
Definition at line 41 of file VerticalPlane.h.
|
protected |
Definition at line 50 of file VerticalPlane.h.