chrono::ChHydraulicActuator3 Class Reference
  Description
Hydraulic actuator using a circuit with 3 volumes.
Schematic:
                  piston      rod
                   side      side
                ___________________
               |   1     |     2   |
 cylinder      |         |----------------
               |___^_____|_____^___|
                   |           |
                   | hose1     |
                   |           | hose2
 throttle         )|(          |
  valve            |           |
                   | hose3     |
                  _|___________|_
 directional     |       X       |
    valve        |___|____ __|___|
                     |       |
                   pump     tankComponents:
- 1 pump and 1 tank, modeled as constant pressures
 - 3 hoses
 - 1 cylinder
 - 1 directional valve 4x3
 - 1 throttle valve States:
 - y(0): U – spool position
 - y(1): p1 – cylinder pressure 1
 - y(2): p2 – cylinder pressure 2
 - y(3): p3 – hose pressure
 
#include <ChHydraulicActuator.h>
Inheritance diagram for chrono::ChHydraulicActuator3:

Collaboration diagram for chrono::ChHydraulicActuator3:

Public Member Functions | |
| void | SetBulkModuli (double oil_bulk_modulus, double hose_bulk_modulus, double cyl_bulk_modulus) | 
| Set the bulk modulus for oil, hoses, and cylinder.  | |
| void | SetHoseVolumes (double hose_tvalve_piston, double hose_dvalve_rod, double hose_dvalve_tvalve) | 
| Set the volumes of the three hoses in this circuit.  | |
| ChHydraulicThrottleValve & | ThrottleValve () | 
| Access the throttle valve in this circuit.  | |
  Public Member Functions inherited from chrono::ChHydraulicActuatorBase | |
| void | SetInputFunction (std::shared_ptr< ChFunction > fun) | 
| Set the actuation function.  More... | |
| void | SetPressures (double pump_pressure, double tank_pressure) | 
| Set the tank and pump pressures.  | |
| void | SetActuatorInitialLength (double len) | 
| Set actuator initial length [m].  More... | |
| void | SetInitialLoad (double initial_load) | 
| Set initial loading force.  More... | |
| virtual void | Initialize () override | 
| Initialize the hydraulic actuator stand-alone.  More... | |
| void | Initialize (std::shared_ptr< ChBody > body1, std::shared_ptr< ChBody > body2, bool local, ChVector3d loc1, ChVector3d loc2) | 
| Initialize this hydraulic actuator by connecting it between the two specified bodies.  More... | |
| ChHydraulicCylinder & | Cylinder () | 
| Access the hydraulic cylinder in this circuit.  | |
| ChHydraulicDirectionalValve4x3 & | DirectionalValve () | 
| Access the directoinal valve in this circuit.  | |
| ChVector3d | GetPoint1Abs () const | 
| Get the endpoint location on 1st body (expressed in absolute coordinate system).  More... | |
| ChVector3d | GetPoint2Abs () const | 
| Get the endpoint location on 2nd body (expressed in body coordinate system).  More... | |
| void | SetActuatorLength (double len, double vel) | 
| Set the current actuator length and rate of change.  More... | |
| double | GetActuatorForce () | 
| Get the current actuator force.  More... | |
| std::array< double, 2 > | GetCylinderPressures () | 
| Get the current cylinder pressures.  | |
| double | GetValvePosition () | 
| Get the current directional valve position.  | |
  Public Member Functions inherited from chrono::ChExternalDynamicsODE | |
| ChVectorDynamic | GetInitialStates () | 
| Get the initial values (state at initial time).  | |
| const ChVectorDynamic & | GetStates () const | 
| Get current states.  | |
| const ChVectorDynamic & | GetRHS () const | 
| Get current RHS.  | |
  Public Member Functions inherited from chrono::ChPhysicsItem | |
| ChPhysicsItem (const ChPhysicsItem &other) | |
| virtual ChPhysicsItem * | Clone () const override | 
| "Virtual" copy constructor (covariant return type).  | |
| ChSystem * | GetSystem () const | 
| Get the pointer to the parent ChSystem().  | |
| virtual void | SetSystem (ChSystem *m_system) | 
| Set the pointer to the parent ChSystem().  More... | |
| virtual bool | IsActive () const | 
| Return true if the object is active and included in dynamics.  | |
| virtual bool | IsCollisionEnabled () const | 
| Tell if the object is subject to collision.  More... | |
| virtual void | AddCollisionModelsToSystem (ChCollisionSystem *coll_sys) const | 
| Add to the provided collision system any collision models managed by this physics item.  More... | |
| virtual void | RemoveCollisionModelsFromSystem (ChCollisionSystem *coll_sys) const | 
| Remove from the provided collision system any collision models managed by this physics item.  More... | |
| virtual void | SyncCollisionModels () | 
| Synchronize the position and bounding box of any collision models managed by this physics item.  | |
| virtual ChAABB | GetTotalAABB () const | 
| Get the axis-aligned bounding box (AABB) of this object.  More... | |
| virtual ChVector3d | GetCenter () const | 
| Get a symbolic 'center' of the object.  More... | |
| virtual void | Setup () | 
| Perform setup operations.  More... | |
| virtual void | ForceToRest () | 
| Set zero speed (and zero accelerations) in state, without changing the position.  More... | |
| virtual unsigned int | GetNumCoordsVelLevel () | 
| Get the number of coordinates at the velocity level.  More... | |
| virtual unsigned int | GetNumConstraints () | 
| Get the number of scalar constraints.  | |
| virtual unsigned int | GetNumConstraintsBilateral () | 
| Get the number of bilateral scalar constraints.  | |
| virtual unsigned int | GetNumConstraintsUnilateral () | 
| Get the number of unilateral scalar constraints.  | |
| unsigned int | GetOffset_x () | 
| Get offset in the state vector (position part)  | |
| unsigned int | GetOffset_w () | 
| Get offset in the state vector (speed part)  | |
| unsigned int | GetOffset_L () | 
| Get offset in the lagrangian multipliers.  | |
| void | SetOffset_x (const unsigned int moff) | 
| Set offset in the state vector (position part) Note: only the ChSystem::Setup function should use this.  | |
| void | SetOffset_w (const unsigned int moff) | 
| Set offset in the state vector (speed part) Note: only the ChSystem::Setup function should use this.  | |
| void | SetOffset_L (const unsigned int moff) | 
| Set offset in the lagrangian multipliers Note: only the ChSystem::Setup function should use this.  | |
| virtual void | IntStateGatherReactions (const unsigned int off_L, ChVectorDynamic<> &L) | 
| From item's reaction forces to global reaction vector.  More... | |
| virtual void | IntStateScatterReactions (const unsigned int off_L, const ChVectorDynamic<> &L) | 
| From global reaction vector to item's reaction forces.  More... | |
| virtual void | IntStateIncrement (const unsigned int off_x, ChState &x_new, const ChState &x, const unsigned int off_v, const ChStateDelta &Dv) | 
| Computes x_new = x + Dt , using vectors at specified offsets.  More... | |
| virtual void | IntStateGetIncrement (const unsigned int off_x, const ChState &x_new, const ChState &x, const unsigned int off_v, ChStateDelta &Dv) | 
| Computes Dt = x_new - x, using vectors at specified offsets.  More... | |
| virtual void | IntLoadResidual_CqL (const unsigned int off_L, ChVectorDynamic<> &R, const ChVectorDynamic<> &L, const double c) | 
| Takes the term Cq'*L, scale and adds to R at given offset: R += c*Cq'*L.  More... | |
| virtual void | IntLoadConstraint_C (const unsigned int off, ChVectorDynamic<> &Qc, const double c, bool do_clamp, double recovery_clamp) | 
| Takes the term C, scale and adds to Qc at given offset: Qc += c*C.  More... | |
| virtual void | IntLoadConstraint_Ct (const unsigned int off, ChVectorDynamic<> &Qc, const double c) | 
| Takes the term Ct, scale and adds to Qc at given offset: Qc += c*Ct.  More... | |
| virtual void | InjectConstraints (ChSystemDescriptor &descriptor) | 
| Register with the given system descriptor any ChConstraint objects associated with this item.  | |
| virtual void | LoadConstraintJacobians () | 
| Compute and load current Jacobians in encapsulated ChConstraint objects.  | |
| virtual void | ConstraintsBiReset () | 
| Sets to zero the known term (b_i) of encapsulated ChConstraints.  | |
| virtual void | ConstraintsBiLoad_C (double factor=1, double recovery_clamp=0.1, bool do_clamp=false) | 
| Adds the current C (constraint violation) to the known term (b_i) of encapsulated ChConstraints.  | |
| virtual void | ConstraintsBiLoad_Ct (double factor=1) | 
| Adds the current Ct (partial t-derivative, as in C_dt=0-> [Cq]*q_dt=-Ct) to the known term (b_i) of encapsulated ChConstraints.  | |
| virtual void | ConstraintsBiLoad_Qc (double factor=1) | 
| Adds the current Qc (the vector of C_dtdt=0 -> [Cq]*q_dtdt=Qc ) to the known term (b_i) of encapsulated ChConstraints.  | |
| virtual void | ConstraintsFetch_react (double factor=1) | 
| Fetches the reactions from the lagrangian multiplier (l_i) of encapsulated ChConstraints.  More... | |
| virtual void | ArchiveOut (ChArchiveOut &archive_out) override | 
| Method to allow serialization of transient data to archives.  | |
| virtual void | ArchiveIn (ChArchiveIn &archive_in) override | 
| Method to allow deserialization of transient data from archives.  More... | |
  Public Member Functions inherited from chrono::ChObj | |
| ChObj (const ChObj &other) | |
| int | GetIdentifier () const | 
| Get the unique integer identifier of this object.  More... | |
| void | SetTag (int tag) | 
| Set an object integer tag (default: -1).  More... | |
| int | GetTag () const | 
| Get the tag of this object.  | |
| void | SetName (const std::string &myname) | 
| Set the name of this object.  | |
| const std::string & | GetName () const | 
| Get the name of this object.  | |
| double | GetChTime () const | 
| Gets the simulation time of this object.  | |
| void | SetChTime (double m_time) | 
| Sets the simulation time of this object.  | |
| void | AddVisualModel (std::shared_ptr< ChVisualModel > model) | 
| Add an (optional) visualization model.  More... | |
| std::shared_ptr< ChVisualModel > | GetVisualModel () const | 
| Access the visualization model (if any).  More... | |
| void | AddVisualShape (std::shared_ptr< ChVisualShape > shape, const ChFrame<> &frame=ChFrame<>()) | 
| Add the specified visual shape to the visualization model.  More... | |
| std::shared_ptr< ChVisualShape > | GetVisualShape (unsigned int i) const | 
| Access the specified visualization shape in the visualization model (if any).  More... | |
| void | AddVisualShapeFEA (std::shared_ptr< ChVisualShapeFEA > shapeFEA) | 
| Add the specified FEA visualization object to the visualization model.  More... | |
| std::shared_ptr< ChVisualShapeFEA > | GetVisualShapeFEA (unsigned int i) const | 
| Access the specified FEA visualization object in the visualization model (if any).  More... | |
| virtual ChFrame | GetVisualModelFrame (unsigned int nclone=0) const | 
| Get the reference frame (expressed in and relative to the absolute frame) of the visual model.  More... | |
| virtual unsigned int | GetNumVisualModelClones () const | 
| Return the number of clones of the visual model associated with this object.  More... | |
| void | AddCamera (std::shared_ptr< ChCamera > camera) | 
| Attach a camera to this object.  More... | |
| std::vector< std::shared_ptr< ChCamera > > | GetCameras () const | 
| Get the set of cameras attached to this object.  | |
| void | UpdateVisualModel () | 
| Utility function to update only the associated visual assets (if any).  | |
| virtual std::string & | ArchiveContainerName () | 
Additional Inherited Members | |
  Protected Member Functions inherited from chrono::ChHydraulicActuatorBase | |
| double | GetInput (double t) const | 
| Get current actuator input.  | |
| virtual bool | IsStiff () const override | 
| Declare the EOM of this physics item as stiff or non-stiff.  | |
| virtual void | Update (double time, bool update_assets) override | 
| Update the physics item at current state.  | |
| virtual void | IntLoadResidual_F (const unsigned int off, ChVectorDynamic<> &R, const double c) override | 
| Load generalized forces.  | |
  Protected Member Functions inherited from chrono::ChExternalDynamicsODE | |
| virtual unsigned int | GetNumCoordsPosLevel () override | 
| Get the number of coordinates at the position level.  More... | |
| ChVariables & | Variables () | 
| virtual void | InjectVariables (ChSystemDescriptor &descriptor) override | 
| Register with the given system descriptor any ChVariable objects associated with this item.  | |
| virtual void | InjectKRMMatrices (ChSystemDescriptor &descriptor) override | 
| Register with the given system descriptor any ChKRMBlock objects associated with this item.  | |
| virtual void | IntStateGather (const unsigned int off_x, ChState &x, const unsigned int off_v, ChStateDelta &v, double &T) override | 
| From item's state to global state vectors y={x,v} pasting the states at the specified offsets.  More... | |
| virtual void | IntStateScatter (const unsigned int off_x, const ChState &x, const unsigned int off_v, const ChStateDelta &v, const double T, bool full_update) override | 
| From global state vectors y={x,v} to item's state (and update) fetching the states at the specified offsets.  More... | |
| virtual void | IntStateGatherAcceleration (const unsigned int off_a, ChStateDelta &a) override | 
| From item's state acceleration to global acceleration vector.  More... | |
| virtual void | IntStateScatterAcceleration (const unsigned int off_a, const ChStateDelta &a) override | 
| From global acceleration vector to item's state acceleration.  More... | |
| virtual void | IntLoadResidual_Mv (const unsigned int off, ChVectorDynamic<> &R, const ChVectorDynamic<> &v, const double c) override | 
| Takes the M*v term, multiplying mass by a vector, scale and adds to R at given offset: R += c*M*w.  More... | |
| virtual void | IntLoadLumpedMass_Md (const unsigned int off, ChVectorDynamic<> &Md, double &err, const double c) override | 
| Adds the lumped mass to a Md vector, representing a mass diagonal matrix.  More... | |
| virtual void | IntToDescriptor (const unsigned int off_v, const ChStateDelta &v, const ChVectorDynamic<> &R, const unsigned int off_L, const ChVectorDynamic<> &L, const ChVectorDynamic<> &Qc) override | 
| Prepare variables and constraints to accommodate a solution:  More... | |
| virtual void | IntFromDescriptor (const unsigned int off_v, ChStateDelta &v, const unsigned int off_L, ChVectorDynamic<> &L) override | 
| After a solver solution, fetch values from variables and constraints into vectors:  More... | |
| virtual void | LoadKRMMatrices (double Kfactor, double Rfactor, double Mfactor) override | 
| Compute and load current stiffnes (K), damping (R), and mass (M) matrices in encapsulated ChKRMBlock objects.  More... | |
| virtual void | VariablesFbReset () override | 
| Sets the 'fb' part (the known term) of the encapsulated ChVariables to zero.  | |
| virtual void | VariablesFbLoadForces (double factor=1) override | 
| Adds the current forces (applied to item) into the encapsulated ChVariables, in the 'fb' part: qf+=forces*factor.  | |
| virtual void | VariablesQbLoadSpeed () override | 
| Initialize the 'qb' part of the ChVariables with the current value of speeds.  More... | |
| virtual void | VariablesQbSetSpeed (double step=0) override | 
| Fetches the item speed (ex.  More... | |
| virtual void | VariablesFbIncrementMq () override | 
| Adds M*q (masses multiplied current 'qb') to Fb, ex.  More... | |
| virtual void | VariablesQbIncrementPosition (double step) override | 
| Increment item positions by the 'qb' part of the ChVariables, multiplied by a 'step' factor.  More... | |
| virtual void | ConstraintsFbLoadForces (double factor=1) override | 
| Adds the current link-forces, if any, (caused by springs, etc.) to the 'fb' vectors of the ChVariables referenced by encapsulated ChConstraints.  | |
  Protected Member Functions inherited from chrono::ChObj | |
| int | GenerateUniqueIdentifier () | 
  Protected Attributes inherited from chrono::ChHydraulicActuatorBase | |
| bool | is_attached | 
| true if actuator attached to bodies  | |
| ChBody * | m_body1 | 
| first conected body  | |
| ChBody * | m_body2 | 
| second connected body  | |
| ChVector3d | m_loc1 | 
| point on body 1 (local frame)  | |
| ChVector3d | m_loc2 | 
| point on body 2 (local frame)  | |
| ChVector3d | m_aloc1 | 
| point on body 1 (global frame)  | |
| ChVector3d | m_aloc2 | 
| point on body 2 (global frame)  | |
| ChVectorDynamic | m_Qforce | 
| generalized forcing terms  | |
| ChHydraulicCylinder | cyl | 
| hydraulic cylinder  | |
| ChHydraulicDirectionalValve4x3 | dvalve | 
| directional valve  | |
| std::shared_ptr< ChFunction > | ref_fun | 
| actuation function (spool displacement reference)  | |
| double | s_0 | 
| initial actuator length [m]  | |
| double | s | 
| current actuator length [m]  | |
| double | sd | 
| current actuator speed [m/s]  | |
| double | pP | 
| pump pressure [Pa]  | |
| double | pT | 
| tank pressure [Pa]  | |
| bool | calculate_consistent_IC | 
| solve initialization nonlinear system  | |
| double | F0 | 
| estimated initial load  | |
  Protected Attributes inherited from chrono::ChPhysicsItem | |
| ChSystem * | system | 
| parent system  | |
| unsigned int | offset_x | 
| offset in vector of state (position part)  | |
| unsigned int | offset_w | 
| offset in vector of state (speed part)  | |
| unsigned int | offset_L | 
| offset in vector of lagrangian multipliers  | |
  Protected Attributes inherited from chrono::ChObj | |
| double | ChTime | 
| object simulation time  | |
| std::string | m_name | 
| object name  | |
| int | m_identifier | 
| object unique identifier  | |
| int | m_tag | 
| user-supplied tag  | |
| std::shared_ptr< ChVisualModelInstance > | vis_model_instance | 
| instantiated visualization model  | |
| std::vector< std::shared_ptr< ChCamera > > | cameras | 
| set of cameras  | |
The documentation for this class was generated from the following files:
- /builds/uwsbel/chrono/src/chrono/physics/ChHydraulicActuator.h
 - /builds/uwsbel/chrono/src/chrono/physics/ChHydraulicActuator.cpp
 
 Public Member Functions inherited from