|
mbsim
4.0.0
MBSim Kernel
|
basic class of MBSim mainly for plotting More...
#include <element.h>
Public Types | |
| enum | InitStage { resolveStringRef =0 , preInit , plotting , unknownStage , LASTINITSTAGE } |
| The stages of the initialization. More... | |
| enum class | PlotAttributeStorage { attribute , dataset } |
Public Member Functions | |
| Element (const std::string &name) | |
| constructor | |
| ~Element () override=default | |
| destructor | |
| void | throwError (const std::string &msg) const |
| virtual void | setDynamicSystemSolver (DynamicSystemSolver *sys) |
| sets the used dynamics system solver to the element More... | |
| virtual void | plot () |
| plots time dependent data More... | |
| virtual void | plotAtSpecialEvent () |
| plots time dependent data at special events More... | |
| const std::string & | getName () const |
| void | setName (const std::string &str) |
| void | setPath (const std::string &str) |
| DynamicSystemSolver * | getDynamicSystemSolver () |
| virtual void | init (InitStage stage, const InitConfigSet &config=InitConfigSet()) |
| plots time series header More... | |
| virtual void | createPlotGroup () |
| creates the plotGroup for H5-output More... | |
| H5::GroupBase * | getPlotGroup () |
| virtual H5::GroupBase * | getFramesPlotGroup () |
| virtual H5::GroupBase * | getContoursPlotGroup () |
| virtual H5::GroupBase * | getGroupsPlotGroup () |
| virtual H5::GroupBase * | getObjectsPlotGroup () |
| virtual H5::GroupBase * | getLinksPlotGroup () |
| virtual H5::GroupBase * | getConstraintsPlotGroup () |
| virtual H5::GroupBase * | getObserversPlotGroup () |
| bool | getPlotFeature (const PlotFeatureEnum &pf) |
| virtual void | setPlotFeature (const PlotFeatureEnum &pf, bool value) |
| Set a plot feature. More... | |
| void | setPlotFeatureForChildren (const PlotFeatureEnum &pf, bool value) |
| Set a plot feature for the children of this object. More... | |
| void | setPlotFeatureRecursive (const PlotFeatureEnum &pf, bool value) |
| Set a plot feature for this object and the children of this object. More... | |
| template<class T > | |
| void | setPlotAttribute (const std::string &name, const T &value, PlotAttributeStorage storage=PlotAttributeStorage::attribute) |
| Set a plot attribute: static data attached as key/value pairs to the plot datasets/groups. | |
| void | setPlotAttribute (const std::string &name, PlotAttributeStorage storage=PlotAttributeStorage::attribute) |
| virtual void | initializeUsingXML (xercesc::DOMElement *element) |
| template<class T > | |
| T * | getByPath (const std::string &path, bool initialCaller=true) const |
| Get the object of type T represented by the path path. Do not set any argurment other than path! | |
| std::string | getPath (const Element *relTo=nullptr, std::string sep="/") const |
| Return the path of this object. If relativeTo is not NULL return a relative path to relativeTo. Do not set any argurment other than relTo and sep! | |
| virtual Element * | getChildByContainerAndName (const std::string &container, const std::string &name) const |
| Get the Element named name in the container named container. More... | |
| virtual std::shared_ptr< OpenMBV::Group > | getOpenMBVGrp () |
| virtual std::shared_ptr< OpenMBV::Group > | getFramesOpenMBVGrp () |
| virtual std::shared_ptr< OpenMBV::Group > | getContoursOpenMBVGrp () |
| virtual std::shared_ptr< OpenMBV::Group > | getGroupsOpenMBVGrp () |
| virtual std::shared_ptr< OpenMBV::Group > | getObjectsOpenMBVGrp () |
| virtual std::shared_ptr< OpenMBV::Group > | getLinksOpenMBVGrp () |
| virtual std::shared_ptr< OpenMBV::Group > | getConstraintsOpenMBVGrp () |
| virtual std::shared_ptr< OpenMBV::Group > | getObserversOpenMBVGrp () |
| virtual Element * | getParent () |
| virtual const Element * | getParent () const |
| virtual void | setParent (Element *parent_) |
| std::vector< Element * > | getDependencies () const |
| checks dependency on other elements. More... | |
| void | addDependency (Element *ele) |
| int | computeLevel () |
| computes the length of the pathes in the graph that represents the dependencies between all elements. More... | |
| virtual void | updatePositions (Frame *frame) |
| virtual void | updateVelocities (Frame *frame) |
| virtual void | updateAccelerations (Frame *frame) |
| virtual void | updateJacobians (Frame *frame, int j=0) |
| virtual void | updateGyroscopicAccelerations (Frame *frame) |
| virtual void | resetUpToDate () |
| const double & | getTime () const |
| double | getStepSize () const |
| const MBXMLUtils::DOMEvalException & | getDOMEvalError () const |
| void | addToPlot (const std::string &name) |
| void | addToPlot (const std::string &name, int size) |
| void | addToPlot (const std::string &name, const std::vector< std::string > &iname) |
| template<class AT > | |
| void | plot (const AT &x) |
| template<class Type , class AT > | |
| void | plot (const fmatvec::Vector< Type, AT > &x) |
Protected Member Functions | |
| void | updatePlotFeatures () |
Protected Attributes | |
| Element * | parent { nullptr } |
| std::string | name |
| name of element | |
| std::string | path |
| The path of this object. Is set during the init stage reorganizeHierarchy. Before this the path is calculated dynamically using getPath() after this stage getPath just returns this value. | |
| MBXMLUtils::DOMEvalException | domEvalError |
| Special XML helper variable. | |
| DynamicSystemSolver * | ds { nullptr } |
| dynamic system | |
| H5::VectorSerie< double > * | plotVectorSerie { nullptr } |
| time series | |
| std::vector< double > | plotVector |
| one entry of time series | |
| std::vector< std::string > | plotColumns |
| columns of time series | |
| H5::GroupBase * | plotGroup { nullptr } |
| associated plot group | |
| std::vector< Element * > | dependency |
| vector containing all dependencies. | |
| PlotFeatureMap | plotFeature |
| plot feature | |
| PlotFeatureMap | plotFeatureForChildren |
| std::map< std::string, std::pair< PlotAttributeStorage, std::variant< std::monostate, int, double, std::string, std::vector< int >, std::vector< double >, std::vector< std::vector< double > > > > > | plotAttribute |
Private Member Functions | |
| Element * | getByPathElement (const std::string &path, bool initialCaller=true) const |
basic class of MBSim mainly for plotting
The stages of the initialization.
see also DynamicSystemSolver::init()
| int MBSim::Element::computeLevel | ( | ) |
computes the length of the pathes in the graph that represents the dependencies between all elements.
|
virtual |
creates the plotGroup for H5-output
Reimplemented in MBSim::Constraint, MBSim::Contour, MBSim::Frame, MBSim::Link, MBSim::Body, MBSim::Object, and MBSim::Observer.
|
inlinevirtual |
Get the Element named name in the container named container.
Reimplemented in MBSim::DynamicSystem, and MBSim::Body.
|
inline |
checks dependency on other elements.
|
inline |
|
inline |
|
inline |
Get the state of the plot feature pf. Returns false if the plot feature pf is not set till now.
|
inline |
|
virtual |
plots time series header
| invocing | parent class |
Reimplemented in MBSim::PolarContourFunction, MBSim::TwoDimensionalPiecewisePolynomFunction< Ret(Arg, Arg)>, MBSim::PlanarStribeckFriction, MBSim::PlanarStribeckImpact, MBSim::RegularizedConstraint, MBSim::RegularizedFriction, MBSim::SpatialStribeckFriction, MBSim::SpatialStribeckImpact, MBSim::GeneralizedConnectionConstraint, MBSim::GeneralizedPositionConstraint, MBSim::BidirectionalFunction< Ret(Arg)>, MBSim::CompositeFunction< Ret(Argo(Argi))>, MBSim::ContinuedFunction< Ret(Arg)>, MBSim::FourierFunction< Ret(Arg)>, MBSim::LinearRegularizedStribeckFriction, MBSim::NonlinearSpringDamperForce, MBSim::PiecewiseDefinedFunction< Ret(Arg)>, MBSim::PolynomFunction< Ret(Arg)>, MBSim::StateDependentFunction< Ret >, MBSim::SymbolicFunction< Ret(Arg)>, MBSim::SymbolicFunction< Ret(Arg1, Arg2)>, MBSim::TabularFunction< Ret(Arg)>, MBSim::TimeDependentFunction< Ret >, MBSim::TwoDimensionalTabularFunction< Ret(Arg1, Arg2)>, MBSim::VectorValuedFunction< Ret(Arg)>, MBSim::PiecewisePolynomFunction< Ret(Arg)>, MBSim::IsotropicRotationalSpringDamper, MBSim::SpringDamper, MBSim::FrameObserver, MBSim::RigidBodyObserver, MBSim::MagicFormula62, MBSim::GeneralizedAccelerationConstraint, MBSim::GeneralizedConstraint, MBSim::GeneralizedDualConstraint, MBSim::GeneralizedGearConstraint, MBSim::GeneralizedVelocityConstraint, MBSim::InverseKinematicsConstraint, MBSim::JointConstraint, MBSim::BevelGear, MBSim::Circle, MBSim::CompoundContour, MBSim::ContourQuad, MBSim::Cuboid, MBSim::Cylinder, MBSim::CylindricalGear, MBSim::Disk, MBSim::Extrusion, MBSim::Frustum, MBSim::LineSegment, MBSim::PlanarContour, MBSim::PlanarFrustum, MBSim::PlanarGear, MBSim::PlanarNurbsContour, MBSim::Plate, MBSim::Point, MBSim::PolynomialFrustum, MBSim::Rack, MBSim::Revolution, MBSim::RigidContour, MBSim::Room, MBSim::SpatialContour, MBSim::SpatialNurbsContour, MBSim::Sphere, MBSim::Tyre, MBSim::DynamicSystem, MBSim::DynamicSystemSolver, MBSim::FixedRelativeFrame, MBSim::FloatingRelativeFrame, MBSim::Frame, MBSim::LinearElasticFunction, MBSim::Contact, MBSim::ContourLink, MBSim::DirectionalSpringDamper, MBSim::DiskContact, MBSim::DualRigidBodyLink, MBSim::ElasticJoint, MBSim::FixedFrameLink, MBSim::FloatingFrameLink, MBSim::FrameLink, MBSim::GeneralizedAccelerationExcitation, MBSim::GeneralizedClutch, MBSim::GeneralizedConnection, MBSim::GeneralizedElasticConnection, MBSim::GeneralizedElasticStructure, MBSim::GeneralizedFriction, MBSim::GeneralizedGear, MBSim::GeneralizedInitialPosition, MBSim::GeneralizedInitialVelocity, MBSim::GeneralizedKinematicExcitation, MBSim::GeneralizedPositionExcitation, MBSim::GeneralizedSpringDamper, MBSim::GeneralizedVelocityExcitation, MBSim::InitialCondition, MBSim::Joint, MBSim::InverseKineticsJoint, MBSim::KineticExcitation, MBSim::Link, MBSim::MaxwellContact, MBSim::MechanicalLink, MBSim::RigidBodyLink, MBSim::SingleContact, MBSim::TyreContact, MBSim::Body, MBSim::Object, MBSim::RigidBody, MBSim::ContactObserver, MBSim::InverseKinematicsConstraintObserver, MBSim::MaxwellContactObserver, MBSim::MechanicalConstraintObserver, MBSim::MechanicalLinkObserver, MBSim::Observer, MBSim::SingleContactObserver, and MBSim::TyreContactObserver.
|
virtual |
Reimplemented in MBSim::PiecewisePolynomFunction< Ret(Arg)>.
|
virtual |
plots time dependent data
| simulation | time |
| simulation | time step size for derivative calculation |
Reimplemented in MBSim::TyreModel, MBSim::SpringDamper, MBSim::FrameObserver, MBSim::RigidBodyObserver, MBSim::CompoundContour, MBSim::RigidContour, MBSim::DynamicSystem, MBSim::DynamicSystemSolver, MBSim::Frame, MBSim::Contact, MBSim::DirectionalSpringDamper, MBSim::GeneralizedClutch, MBSim::GeneralizedFriction, MBSim::InitialCondition, MBSim::KineticExcitation, MBSim::Link, MBSim::MaxwellContact, MBSim::MechanicalLink, MBSim::TyreContact, MBSim::Body, MBSim::Object, MBSim::RigidBody, MBSim::ContactObserver, MBSim::InverseKinematicsConstraintObserver, MBSim::MaxwellContactObserver, MBSim::MechanicalConstraintObserver, MBSim::MechanicalLinkObserver, MBSim::SingleContactObserver, and MBSim::TyreContactObserver.
|
inlinevirtual |
plots time dependent data at special events
| simulation | time |
| simulation | time step size for derivative calculation |
Reimplemented in MBSim::DynamicSystem.
|
inlinevirtual |
sets the used dynamics system solver to the element
| pointer | to the dynamic system solver of which the element is part of |
Reimplemented in MBSim::DynamicSystem, MBSim::StateDependentFunction< Ret >, MBSim::TimeDependentFunction< Ret >, MBSim::Contact, MBSim::MaxwellContact, MBSim::Body, MBSim::RigidBody, MBSim::ContactObserver, and MBSim::MaxwellContactObserver.
|
inline |
| element | name |
|
virtual |
Set a plot feature.
Set the plot feature pf of this object.
| void MBSim::Element::setPlotFeatureForChildren | ( | const PlotFeatureEnum & | pf, |
| bool | value | ||
| ) |
Set a plot feature for the children of this object.
Set the plot feature pf of all children for set plot features.
|
inline |
Set a plot feature for this object and the children of this object.
This is a convenience function. It simply calls setPlotFeature and setPlotFeatureForChildren.