SOFA API  384d495c
Open source framework for multi-physics simuation
sofa::component::statecontainer::MechanicalObject< DataTypes > Class Template Reference

#include <MechanicalObject.h>

This class can be overridden if needed for additionnal storage within template specializations. More...

Inheritance diagram for sofa::component::statecontainer::MechanicalObject< DataTypes >:

Detailed Description

template<class DataTypes>
class sofa::component::statecontainer::MechanicalObject< DataTypes >

This class can be overridden if needed for additionnal storage within template specializations.

MechanicalObject class.

Public Attributes

Data< VecCoordx
 position coordinates of the degrees of freedom More...
 
Data< VecDerivv
 velocity coordinates of the degrees of freedom More...
 
Data< VecDerivf
 force vector of the degrees of freedom More...
 
Data< VecCoordx0
 rest position coordinates of the degrees of freedom More...
 
Data< VecDerivexternalForces
 externalForces vector of the degrees of freedom More...
 
Data< VecDerivdx
 dx vector of the degrees of freedom More...
 
Data< VecCoordxfree
 free position coordinates of the degrees of freedom More...
 
Data< VecDerivvfree
 free velocity coordinates of the degrees of freedom More...
 
Data< MatrixDerivc
 constraints applied to the degrees of freedom More...
 
Data< MatrixDerivm
 mappingJacobian applied to the degrees of freedom More...
 
Data< VecCoordreset_position
 reset position coordinates of the degrees of freedom More...
 
Data< VecDerivreset_velocity
 reset velocity coordinates of the degrees of freedom More...
 
defaulttype::MapMapSparseMatrix< Derivc2
 
Data< SRealrestScale
 optional scaling of rest position coordinates (to simulated pre-existing internal tension).(default = 1.0) More...
 
Data< bool > d_useTopology
 Shall this object rely on any active topology to initialize its size and positions. More...
 
Data< bool > showObject
 Show objects. (default=false) More...
 
Data< floatshowObjectScale
 Scale for object display. (default=0.1) More...
 
Data< bool > showIndices
 Show indices. (default=false) More...
 
Data< floatshowIndicesScale
 Scale for indices display. (default=0.02) More...
 
Data< bool > showVectors
 Show velocity. (default=false) More...
 
Data< floatshowVectorsScale
 Scale for vectors display. (default=0.0001) More...
 
Data< intdrawMode
 The way vectors will be drawn: - 0: Line - 1:Cylinder - 2: Arrow. The DOFS will be drawn: - 0: point - >1: sphere. (default=0) More...
 
Data< type::RGBAColord_color
 drawing color More...
 

Protected Attributes

Data< intd_size
 Size of the vectors. More...
 
SingleLink< MechanicalObject< DataTypes >, core::topology::BaseMeshTopology, BaseLink::FLAG_STRONGLINK|BaseLink::FLAG_STOREPATHl_topology
 
Data< intf_reserve
 Size to reserve when creating vectors. (default=0) More...
 
bool m_initialized
 
MechanicalObjectInternalData< DataTypesdata
 Given the number of a constraint Equation, find the index in the MatrixDeriv C, where the constraint is actually stored. More...
 
std::ofstream * m_gnuplotFileX
 
std::ofstream * m_gnuplotFileV
 
Initial geometric transformations
Data< type::Vec3translation
 Translation of the DOFs. More...
 
Data< type::Vec3rotation
 Rotation of the DOFs. More...
 
Data< type::Vec3scale
 Scale of the DOFs in 3 dimensions. More...
 
Data< type::Vec3translation2
 Translation of the DOFs, applied after the rest position has been computed. More...
 
Data< type::Vec3rotation2
 Rotation of the DOFs, applied the after the rest position has been computed. More...
 

Public Member Functions

 SOFA_CLASS (SOFA_TEMPLATE(MechanicalObject, DataTypes), SOFA_TEMPLATE(sofa::core::behavior::MechanicalState, DataTypes))
 
 SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER (Vector3, sofa::type::Vec3)
 
 SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER (Index, sofa::Index)
 
MechanicalObjectoperator= (const MechanicalObject &)
 
void parse (core::objectmodel::BaseObjectDescription *arg) override
 
void init () override
 
void reinit () override
 
void storeResetState () override
 
void reset () override
 
void writeVec (core::ConstVecId v, std::ostream &out) override
 
void readVec (core::VecId v, std::istream &in) override
 
SReal compareVec (core::ConstVecId v, std::istream &in) override
 
void writeState (std::ostream &out) override
 
void initGnuplot (const std::string path) override
 
void exportGnuplot (SReal time) override
 
void resize (Size vsize) override
 
virtual void reserve (Size vsize)
 
Size getSize () const override
 
SReal getPX (sofa::Index i) const override
 
SReal getPY (sofa::Index i) const override
 
SReal getPZ (sofa::Index i) const override
 
SReal getVX (sofa::Index i) const
 
SReal getVY (sofa::Index i) const
 
SReal getVZ (sofa::Index i) const
 
void replaceValue (const sofa::Index inputIndex, const sofa::Index outputIndex)
 Overwrite values at index outputIndex by the ones at inputIndex. More...
 
void swapValues (const sofa::Index idx1, const sofa::Index idx2)
 Exchange values at indices idx1 and idx2. More...
 
void renumberValues (const sofa::type::vector< sofa::Index > &index)
 Reorder values according to parameter. More...
 
void computeWeightedValue (const sofa::Index i, const sofa::type::vector< sofa::Index > &ancestors, const sofa::type::vector< double > &coefs)
 Replace the value at index by the sum of the ancestors values weithed by the coefs. More...
 
void forcePointPosition (const sofa::Index i, const sofa::type::vector< double > &m_x)
 Force the position of a point (and force its velocity to zero value) More...
 
void getIndicesInSpace (sofa::type::vector< sofa::Index > &indices, Real xmin, Real xmax, Real ymin, Real ymax, Real zmin, Real zmax) const override
 Get the indices of the particles located in the given bounding box. More...
 
bool addBBox (SReal *minBBox, SReal *maxBBox) override
 update the given bounding box, to include this More...
 
void computeBBox (const core::ExecParams *params, bool onlyVisible=false) override
 Bounding Box computation method. More...
 
virtual std::list< ConstraintBlockconstraintBlocks (const std::list< unsigned int > &indices) const override
 Express the matrix L in term of block of matrices, using the indices of the lines in the MatrixDeriv container. More...
 
SReal getConstraintJacobianTimesVecDeriv (unsigned int line, core::ConstVecId id) override
 
void handleStateChange () override
 
bool pickParticles (const core::ExecParams *params, double rayOx, double rayOy, double rayOz, double rayDx, double rayDy, double rayDz, double radius0, double dRadius, std::multimap< double, std::pair< sofa::core::behavior::BaseMechanicalState *, int > > &particles) override
 
bool isIndependent () const
 if this mechanical object stores independent dofs (in opposition to mapped dofs) More...
 
void applyRotation (const type::Quat< SReal > q)
 
void addFromBaseVectorDifferentSize (core::VecId dest, const linearalgebra::BaseVector *src, unsigned int &offset)
 
void addFromBaseVectorSameSize (core::VecId dest, const linearalgebra::BaseVector *src, unsigned int &offset)
 
void draw (const core::visual::VisualParams *vparams)
 
SOFA_COMPONENT_STATECONTAINER_API void applyRotation (const type::Quat< SReal > q)
 
SOFA_COMPONENT_STATECONTAINER_API void addFromBaseVectorSameSize (core::VecId dest, const linearalgebra::BaseVector *src, unsigned int &offset)
 
SOFA_COMPONENT_STATECONTAINER_API void addFromBaseVectorDifferentSize (core::VecId dest, const linearalgebra::BaseVector *src, unsigned int &offset)
 
SOFA_COMPONENT_STATECONTAINER_API void draw (const core::visual::VisualParams *vparams)
 
New vectors access API based on VecId
Data< VecCoord > * write (core::VecCoordId v) override
 
const Data< VecCoord > * read (core::ConstVecCoordId v) const override
 
Data< VecDeriv > * write (core::VecDerivId v) override
 
const Data< VecDeriv > * read (core::ConstVecDerivId v) const override
 
Data< MatrixDeriv > * write (core::MatrixDerivId v) override
 
const Data< MatrixDeriv > * read (core::ConstMatrixDerivId v) const override
 
Initial transformations application methods.
void applyTranslation (const SReal dx, const SReal dy, const SReal dz) override
 Apply translation vector to the position. More...
 
void applyRotation (const SReal rx, const SReal ry, const SReal rz) override
 Rotation using Euler Angles in degree. More...
 
void applyRotation (const type::Quat< SReal > q) override
 
void applyScale (const SReal sx, const SReal sy, const SReal sz) override
 
Base Matrices and Vectors Interface
void copyToBaseVector (linearalgebra::BaseVector *dest, core::ConstVecId src, unsigned int &offset) override
 
void copyFromBaseVector (core::VecId dest, const linearalgebra::BaseVector *src, unsigned int &offset) override
 
void copyToBaseMatrix (linearalgebra::BaseMatrix *dest, core::ConstMatrixDerivId src, unsigned int &offset) override
 Copy data to a global BaseMatrix from the state stored in a local vector. More...
 
void addToBaseVector (linearalgebra::BaseVector *dest, core::ConstVecId src, unsigned int &offset) override
 
void addFromBaseVectorSameSize (core::VecId dest, const linearalgebra::BaseVector *src, unsigned int &offset) override
 
void addFromBaseVectorDifferentSize (core::VecId dest, const linearalgebra::BaseVector *src, unsigned int &offset) override
 
Initial transformations accessors.
void setTranslation (SReal dx, SReal dy, SReal dz)
 
void setRotation (SReal rx, SReal ry, SReal rz)
 
void setScale (SReal sx, SReal sy, SReal sz)
 
virtual type::Vec3 getTranslation () const
 
virtual type::Vec3 getRotation () const
 
type::Vec3 getScale () const override
 
Integration related methods
void beginIntegration (SReal dt) override
 
void endIntegration (const core::ExecParams *params, SReal dt) override
 
void accumulateForce (const core::ExecParams *params, core::VecDerivId f=core::VecDerivId::force()) override
 
void vAvail (const core::ExecParams *params, core::VecCoordId &v) override
 Increment the index of the given VecCoordId, so that all 'allocated' vectors in this state have a lower index. More...
 
void vAvail (const core::ExecParams *params, core::VecDerivId &v) override
 Increment the index of the given VecDerivId, so that all 'allocated' vectors in this state have a lower index. More...
 
void vAlloc (const core::ExecParams *params, core::VecCoordId v, const core::VecIdProperties &properties={}) override
 Increment the index of the given MatrixDerivId, so that all 'allocated' vectors in this state have a lower index. More...
 
void vAlloc (const core::ExecParams *params, core::VecDerivId v, const core::VecIdProperties &properties={}) override
 Allocate a new temporary vector. More...
 
void vRealloc (const core::ExecParams *params, core::VecCoordId v, const core::VecIdProperties &properties={}) override
 Allocate a new temporary vector. More...
 
void vRealloc (const core::ExecParams *params, core::VecDerivId v, const core::VecIdProperties &properties={}) override
 Reallocate a new temporary vector. More...
 
void vFree (const core::ExecParams *params, core::VecCoordId v) override
 Free a temporary vector. More...
 
void vFree (const core::ExecParams *params, core::VecDerivId v) override
 Free a temporary vector. More...
 
void vInit (const core::ExecParams *params, core::VecCoordId v, core::ConstVecCoordId vSrc) override
 Free a temporary vector. More...
 
void vInit (const core::ExecParams *params, core::VecDerivId v, core::ConstVecDerivId vSrc) override
 Initialize an unset vector. More...
 
void vOp (const core::ExecParams *params, core::VecId v, core::ConstVecId a=core::ConstVecId::null(), core::ConstVecId b=core::ConstVecId::null(), SReal f=1.0) override
 Initialize an unset vector. More...
 
void vMultiOp (const core::ExecParams *params, const VMultiOp &ops) override
 
void vThreshold (core::VecId a, SReal threshold) override
 
SReal vDot (const core::ExecParams *params, core::ConstVecId a, core::ConstVecId b) override
 
SReal vSum (const core::ExecParams *params, core::ConstVecId a, unsigned l) override
 Sum of the entries of state vector a at the power of l>0. This is used to compute the l-norm of the vector. More...
 
SReal vMax (const core::ExecParams *params, core::ConstVecId a) override
 Maximum of the absolute values of the entries of state vector a. This is used to compute the infinite-norm of the vector. More...
 
Size vSize (const core::ExecParams *params, core::ConstVecId v) override
 
void resetForce (const core::ExecParams *params, core::VecDerivId f=core::VecDerivId::force()) override
 
void resetAcc (const core::ExecParams *params, core::VecDerivId a=core::VecDerivId::dx()) override
 
void resetConstraint (const core::ConstraintParams *cparams) override
 
void getConstraintJacobian (const core::ConstraintParams *cparams, sofa::linearalgebra::BaseMatrix *J, unsigned int &off) override
 
void buildIdentityBlocksInJacobian (const sofa::type::vector< unsigned int > &list_n, core::MatrixDerivId &mID) override
 
Debug
void printDOF (core::ConstVecId, std::ostream &=std::cerr, int firstIndex=0, int range=-1) const override
 
unsigned printDOFWithElapsedTime (core::ConstVecId, unsigned=0, unsigned=0, std::ostream &=std::cerr) override
 
void draw (const core::visual::VisualParams *vparams) override
 

Protected Member Functions

 MechanicalObject ()
 
virtual ~MechanicalObject ()
 
template<core::VecType vtype>
void vAvailImpl (core::TVecId< vtype, core::V_WRITE > &v, sofa::type::vector< Data< core::StateVecType_t< DataTypes, vtype > > * > &dataContainer)
 Generic implementation of the method vAvail. More...
 
template<core::VecType vtype>
void vAllocImpl (core::TVecId< vtype, core::V_WRITE > v, const core::VecIdProperties &properties)
 Generic implementation of the method vAlloc. More...
 
template<core::VecType vtype>
void vReallocImpl (core::TVecId< vtype, core::V_WRITE > v, const core::VecIdProperties &properties)
 Generic implementation of the method vRealloc. More...
 
template<core::VecType vtype>
void vFreeImpl (core::TVecId< vtype, core::V_WRITE > v)
 Generic implementation of the method vFree. More...
 
template<core::VecType vtype>
void vInitImpl (const core::ExecParams *params, core::TVecId< vtype, core::V_WRITE > vId, core::TVecId< vtype, core::V_READ > vSrcId)
 Generic implementation of the method vInit. More...
 
template<core::VecType vtype>
helper::WriteOnlyAccessor< core::objectmodel::Data< core::StateVecType_t< DataTypes, vtype > > > getWriteOnlyAccessor (core::VecId v)
 Shortcut to get a write-only accessor corresponding to the provided VecType from a VecId. More...
 
template<core::VecType vtype>
helper::WriteAccessor< core::objectmodel::Data< core::StateVecType_t< DataTypes, vtype > > > getWriteAccessor (core::VecId v)
 Shortcut to get a write accessor corresponding to the provided VecType from a VecId. More...
 
template<core::VecType vtype>
helper::ReadAccessor< core::objectmodel::Data< core::StateVecType_t< DataTypes, vtype > > > getReadAccessor (core::ConstVecId v)
 Shortcut to get a read accessor corresponding to the provided VecType from a VecId. More...
 
void drawIndices (const core::visual::VisualParams *vparams)
 Internal function : Draw indices in 3d coordinates. More...
 
void drawVectors (const core::visual::VisualParams *vparams)
 Internal function : Draw vectors. More...
 

Static Protected Member Functions

template<core::VecType vtype, core::VecAccess vaccess>
static void setVecIdProperties (core::TVecId< vtype, vaccess > v, const core::VecIdProperties &properties, core::BaseData *vec_d)
 

Friends

class MechanicalObjectInternalData< DataTypes >
 

Integration-related data

sofa::type::vector< Data< VecCoord > * > vectorsCoord
 Coordinates DOFs vectors table (static and dynamic allocated) More...
 
sofa::type::vector< Data< VecDeriv > * > vectorsDeriv
 Derivates DOFs vectors table (static and dynamic allocated) More...
 
sofa::type::vector< Data< MatrixDeriv > * > vectorsMatrixDeriv
 Constraint vectors table. More...
 
void setVecCoord (core::ConstVecCoordId, Data< VecCoord > *)
 Inserts VecCoord DOF coordinates vector at index in the vectorsCoord container. More...
 
void setVecDeriv (core::ConstVecDerivId, Data< VecDeriv > *)
 Inserts VecDeriv DOF derivates vector at index in the vectorsDeriv container. More...
 
void setVecMatrixDeriv (core::ConstMatrixDerivId, Data< MatrixDeriv > *)
 Inserts MatrixDeriv DOF at index in the MatrixDeriv container. More...
 

Attribute details

◆ c

constraints applied to the degrees of freedom

◆ c2

◆ d_color

drawing color

◆ d_size

template<class DataTypes >
Data< int > sofa::component::statecontainer::MechanicalObject< DataTypes >::d_size
protected

Size of the vectors.

◆ d_useTopology

template<class DataTypes >
Data< bool > sofa::component::statecontainer::MechanicalObject< DataTypes >::d_useTopology

Shall this object rely on any active topology to initialize its size and positions.

◆ data

Given the number of a constraint Equation, find the index in the MatrixDeriv C, where the constraint is actually stored.

◆ drawMode

template<class DataTypes >
Data< int > sofa::component::statecontainer::MechanicalObject< DataTypes >::drawMode

The way vectors will be drawn: - 0: Line - 1:Cylinder - 2: Arrow. The DOFS will be drawn: - 0: point - >1: sphere. (default=0)

◆ dx

dx vector of the degrees of freedom

◆ externalForces

template<class DataTypes >
Data< VecDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::externalForces

externalForces vector of the degrees of freedom

◆ f

force vector of the degrees of freedom

◆ f_reserve

template<class DataTypes >
Data< int > sofa::component::statecontainer::MechanicalObject< DataTypes >::f_reserve
protected

Size to reserve when creating vectors. (default=0)

◆ l_topology

◆ m

mappingJacobian applied to the degrees of freedom

◆ m_gnuplotFileV

template<class DataTypes >
std::ofstream* sofa::component::statecontainer::MechanicalObject< DataTypes >::m_gnuplotFileV
protected

◆ m_gnuplotFileX

template<class DataTypes >
std::ofstream* sofa::component::statecontainer::MechanicalObject< DataTypes >::m_gnuplotFileX
protected

◆ m_initialized

template<class DataTypes >
bool sofa::component::statecontainer::MechanicalObject< DataTypes >::m_initialized
protected

◆ reset_position

template<class DataTypes >
Data< VecCoord > sofa::component::statecontainer::MechanicalObject< DataTypes >::reset_position

reset position coordinates of the degrees of freedom

◆ reset_velocity

template<class DataTypes >
Data< VecDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::reset_velocity

reset velocity coordinates of the degrees of freedom

◆ restScale

template<class DataTypes >
Data< SReal > sofa::component::statecontainer::MechanicalObject< DataTypes >::restScale

optional scaling of rest position coordinates (to simulated pre-existing internal tension).(default = 1.0)

◆ rotation

template<class DataTypes >
Data< type::Vec3 > sofa::component::statecontainer::MechanicalObject< DataTypes >::rotation
protected

Rotation of the DOFs.

◆ rotation2

template<class DataTypes >
Data< type::Vec3 > sofa::component::statecontainer::MechanicalObject< DataTypes >::rotation2
protected

Rotation of the DOFs, applied the after the rest position has been computed.

◆ scale

template<class DataTypes >
Data< type::Vec3 > sofa::component::statecontainer::MechanicalObject< DataTypes >::scale
protected

Scale of the DOFs in 3 dimensions.

◆ showIndices

template<class DataTypes >
Data< bool > sofa::component::statecontainer::MechanicalObject< DataTypes >::showIndices

Show indices. (default=false)

◆ showIndicesScale

template<class DataTypes >
Data< float > sofa::component::statecontainer::MechanicalObject< DataTypes >::showIndicesScale

Scale for indices display. (default=0.02)

◆ showObject

template<class DataTypes >
Data< bool > sofa::component::statecontainer::MechanicalObject< DataTypes >::showObject

Show objects. (default=false)

◆ showObjectScale

template<class DataTypes >
Data< float > sofa::component::statecontainer::MechanicalObject< DataTypes >::showObjectScale

Scale for object display. (default=0.1)

◆ showVectors

template<class DataTypes >
Data< bool > sofa::component::statecontainer::MechanicalObject< DataTypes >::showVectors

Show velocity. (default=false)

◆ showVectorsScale

template<class DataTypes >
Data< float > sofa::component::statecontainer::MechanicalObject< DataTypes >::showVectorsScale

Scale for vectors display. (default=0.0001)

◆ translation

template<class DataTypes >
Data< type::Vec3 > sofa::component::statecontainer::MechanicalObject< DataTypes >::translation
protected

Translation of the DOFs.

◆ translation2

template<class DataTypes >
Data< type::Vec3 > sofa::component::statecontainer::MechanicalObject< DataTypes >::translation2
protected

Translation of the DOFs, applied after the rest position has been computed.

◆ v

velocity coordinates of the degrees of freedom

◆ vectorsCoord

template<class DataTypes >
sofa::type::vector< Data< VecCoord > * > sofa::component::statecontainer::MechanicalObject< DataTypes >::vectorsCoord
protected

Coordinates DOFs vectors table (static and dynamic allocated)

◆ vectorsDeriv

template<class DataTypes >
sofa::type::vector< Data< VecDeriv > * > sofa::component::statecontainer::MechanicalObject< DataTypes >::vectorsDeriv
protected

Derivates DOFs vectors table (static and dynamic allocated)

◆ vectorsMatrixDeriv

template<class DataTypes >
sofa::type::vector< Data< MatrixDeriv > * > sofa::component::statecontainer::MechanicalObject< DataTypes >::vectorsMatrixDeriv
protected

Constraint vectors table.

◆ vfree

free velocity coordinates of the degrees of freedom

◆ x

position coordinates of the degrees of freedom

◆ x0

rest position coordinates of the degrees of freedom

◆ xfree

free position coordinates of the degrees of freedom

Constructor details

◆ MechanicalObject()

◆ ~MechanicalObject()

template<class DataTypes >
sofa::component::statecontainer::MechanicalObject< DataTypes >::~MechanicalObject
protectedvirtual

Function details

◆ accumulateForce()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::accumulateForce ( const core::ExecParams params,
core::VecDerivId  f = core::VecDerivId::force() 
)
override

◆ addBBox()

template<class DataTypes >
bool sofa::component::statecontainer::MechanicalObject< DataTypes >::addBBox ( SReal minBBox,
SReal maxBBox 
)
override

update the given bounding box, to include this

◆ addFromBaseVectorDifferentSize() [1/3]

void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::addFromBaseVectorDifferentSize ( core::VecId  dest,
const linearalgebra::BaseVector src,
unsigned int offset 
)

◆ addFromBaseVectorDifferentSize() [2/3]

SOFA_COMPONENT_STATECONTAINER_API void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::addFromBaseVectorDifferentSize ( core::VecId  dest,
const linearalgebra::BaseVector src,
unsigned int offset 
)

◆ addFromBaseVectorDifferentSize() [3/3]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::addFromBaseVectorDifferentSize ( core::VecId  dest,
const linearalgebra::BaseVector src,
unsigned int offset 
)
override

src size can be smaller or equal to dest size. Performs: dest[ offset + i ][j] += src[i][j] 0<= i < src_entries 0<= j < 3 (for 3D objects) 0 <= j < 2 (for 2D objects)

Parameters
offsetthe offset in the MechanicalObject local vector specified by VecId dest. It will be updated to the first scalar value after the ones used by this operation when this method returns.

◆ addFromBaseVectorSameSize() [1/3]

void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::addFromBaseVectorSameSize ( core::VecId  dest,
const linearalgebra::BaseVector src,
unsigned int offset 
)

◆ addFromBaseVectorSameSize() [2/3]

SOFA_COMPONENT_STATECONTAINER_API void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::addFromBaseVectorSameSize ( core::VecId  dest,
const linearalgebra::BaseVector src,
unsigned int offset 
)

◆ addFromBaseVectorSameSize() [3/3]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::addFromBaseVectorSameSize ( core::VecId  dest,
const linearalgebra::BaseVector src,
unsigned int offset 
)
override

src and dest must have the same size. Performs: dest[i][j] += src[offset + i][j] 0<= i < src_entries 0<= j < 3 (for 3D objects) 0 <= j < 2 (for 2D objects)

Parameters
offsetthe offset in the BaseVector where the scalar values will be used. It will be updated to the first scalar value after the ones used by this operation when this method returns

◆ addToBaseVector()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::addToBaseVector ( linearalgebra::BaseVector dest,
core::ConstVecId  src,
unsigned int offset 
)
override

Add data to a global BaseVector from the state stored in a local vector

Parameters
offsetthe offset in the BaseVector where the scalar values will be used. It will be updated to the first scalar value after the ones used by this operation when this method returns

◆ applyRotation() [1/4]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::applyRotation ( const SReal  rx,
const SReal  ry,
const SReal  rz 
)
override

Rotation using Euler Angles in degree.

◆ applyRotation() [2/4]

◆ applyRotation() [3/4]

SOFA_COMPONENT_STATECONTAINER_API void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::applyRotation ( const type::Quat< SReal q)

◆ applyRotation() [4/4]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::applyRotation ( const type::Quat< SReal q)
override

◆ applyScale()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::applyScale ( const SReal  sx,
const SReal  sy,
const SReal  sz 
)
override

◆ applyTranslation()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::applyTranslation ( const SReal  dx,
const SReal  dy,
const SReal  dz 
)
override

Apply translation vector to the position.

◆ beginIntegration()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::beginIntegration ( SReal  dt)
override

◆ buildIdentityBlocksInJacobian()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::buildIdentityBlocksInJacobian ( const sofa::type::vector< unsigned int > &  list_n,
core::MatrixDerivId mID 
)
override

◆ compareVec()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::compareVec ( core::ConstVecId  v,
std::istream &  in 
)
override

◆ computeBBox()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::computeBBox ( const core::ExecParams params,
bool  onlyVisible = false 
)
override

Bounding Box computation method.

◆ computeWeightedValue()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::computeWeightedValue ( const sofa::Index  i,
const sofa::type::vector< sofa::Index > &  ancestors,
const sofa::type::vector< double > &  coefs 
)

Replace the value at index by the sum of the ancestors values weithed by the coefs.

Sum of the coefs should usually equal to 1.0

◆ constraintBlocks()

template<class DataTypes >
std::list< core::behavior::BaseMechanicalState::ConstraintBlock > sofa::component::statecontainer::MechanicalObject< DataTypes >::constraintBlocks ( const std::list< unsigned int > &  indices) const
overridevirtual

Express the matrix L in term of block of matrices, using the indices of the lines in the MatrixDeriv container.

◆ copyFromBaseVector()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::copyFromBaseVector ( core::VecId  dest,
const linearalgebra::BaseVector src,
unsigned int offset 
)
override

Copy data to a local vector the state stored in a global BaseVector

Parameters
offsetthe offset in the BaseVector where the scalar values will be used. It will be updated to the first scalar value after the ones used by this operation when this method returns

◆ copyToBaseMatrix()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::copyToBaseMatrix ( linearalgebra::BaseMatrix dest,
core::ConstMatrixDerivId  src,
unsigned int offset 
)
override

Copy data to a global BaseMatrix from the state stored in a local vector.

◆ copyToBaseVector()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::copyToBaseVector ( linearalgebra::BaseVector dest,
core::ConstVecId  src,
unsigned int offset 
)
override

Copy data to a global BaseVector the state stored in a local vector

Parameters
offsetthe offset in the BaseVector where the scalar values will be used. It will be updated to the first scalar value after the ones used by this operation when this method returns

◆ draw() [1/3]

◆ draw() [2/3]

SOFA_COMPONENT_STATECONTAINER_API void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::draw ( const core::visual::VisualParams vparams)

◆ draw() [3/3]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::draw ( const core::visual::VisualParams vparams)
inlineoverride

◆ drawIndices()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::drawIndices ( const core::visual::VisualParams vparams)
inlineprotected

Internal function : Draw indices in 3d coordinates.

◆ drawVectors()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::drawVectors ( const core::visual::VisualParams vparams)
inlineprotected

Internal function : Draw vectors.

◆ endIntegration()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::endIntegration ( const core::ExecParams params,
SReal  dt 
)
override

◆ exportGnuplot()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::exportGnuplot ( SReal  time)
override

◆ forcePointPosition()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::forcePointPosition ( const sofa::Index  i,
const sofa::type::vector< double > &  m_x 
)

Force the position of a point (and force its velocity to zero value)

◆ getConstraintJacobian()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::getConstraintJacobian ( const core::ConstraintParams cparams,
sofa::linearalgebra::BaseMatrix J,
unsigned int off 
)
override

◆ getConstraintJacobianTimesVecDeriv()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::getConstraintJacobianTimesVecDeriv ( unsigned int  line,
core::ConstVecId  id 
)
override

◆ getIndicesInSpace()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::getIndicesInSpace ( sofa::type::vector< sofa::Index > &  indices,
Real  xmin,
Real  xmax,
Real  ymin,
Real  ymax,
Real  zmin,
Real  zmax 
) const
override

Get the indices of the particles located in the given bounding box.

◆ getPX()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::getPX ( sofa::Index  i) const
inlineoverride

◆ getPY()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::getPY ( sofa::Index  i) const
inlineoverride

◆ getPZ()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::getPZ ( sofa::Index  i) const
inlineoverride

◆ getReadAccessor()

template<class DataTypes >
template<core::VecType vtype>
helper::ReadAccessor< core::objectmodel::Data< core::StateVecType_t< DataTypes, vtype > > > sofa::component::statecontainer::MechanicalObject< DataTypes >::getReadAccessor ( core::ConstVecId  v)
protected

Shortcut to get a read accessor corresponding to the provided VecType from a VecId.

◆ getRotation()

template<class DataTypes >
virtual type::Vec3 sofa::component::statecontainer::MechanicalObject< DataTypes >::getRotation ( ) const
inlinevirtual

◆ getScale()

template<class DataTypes >
type::Vec3 sofa::component::statecontainer::MechanicalObject< DataTypes >::getScale ( ) const
inlineoverride

◆ getSize()

template<class DataTypes >
Size sofa::component::statecontainer::MechanicalObject< DataTypes >::getSize ( ) const
inlineoverride

◆ getTranslation()

template<class DataTypes >
virtual type::Vec3 sofa::component::statecontainer::MechanicalObject< DataTypes >::getTranslation ( ) const
inlinevirtual

◆ getVX()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::getVX ( sofa::Index  i) const
inline

◆ getVY()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::getVY ( sofa::Index  i) const
inline

◆ getVZ()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::getVZ ( sofa::Index  i) const
inline

◆ getWriteAccessor()

template<class DataTypes >
template<core::VecType vtype>
helper::WriteAccessor< core::objectmodel::Data< core::StateVecType_t< DataTypes, vtype > > > sofa::component::statecontainer::MechanicalObject< DataTypes >::getWriteAccessor ( core::VecId  v)
protected

Shortcut to get a write accessor corresponding to the provided VecType from a VecId.

◆ getWriteOnlyAccessor()

template<class DataTypes >
template<core::VecType vtype>
helper::WriteOnlyAccessor< core::objectmodel::Data< core::StateVecType_t< DataTypes, vtype > > > sofa::component::statecontainer::MechanicalObject< DataTypes >::getWriteOnlyAccessor ( core::VecId  v)
protected

Shortcut to get a write-only accessor corresponding to the provided VecType from a VecId.

◆ handleStateChange()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::handleStateChange
override

◆ init()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::init
override

◆ initGnuplot()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::initGnuplot ( const std::string  path)
override

◆ isIndependent()

template<class DataTypes >
bool sofa::component::statecontainer::MechanicalObject< DataTypes >::isIndependent

if this mechanical object stores independent dofs (in opposition to mapped dofs)

◆ operator=()

template<class DataTypes >
MechanicalObject< DataTypes > & sofa::component::statecontainer::MechanicalObject< DataTypes >::operator= ( const MechanicalObject< DataTypes > &  obj)

◆ parse()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::parse ( core::objectmodel::BaseObjectDescription arg)
override

◆ pickParticles()

template<class DataTypes >
bool sofa::component::statecontainer::MechanicalObject< DataTypes >::pickParticles ( const core::ExecParams params,
double  rayOx,
double  rayOy,
double  rayOz,
double  rayDx,
double  rayDy,
double  rayDz,
double  radius0,
double  dRadius,
std::multimap< double, std::pair< sofa::core::behavior::BaseMechanicalState *, int > > &  particles 
)
override

Find mechanical particles hit by the given ray. A mechanical particle is defined as a 2D or 3D, position or rigid DOF Returns false if this object does not support picking

◆ printDOF()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::printDOF ( core::ConstVecId  v,
std::ostream &  out = std::cerr,
int  firstIndex = 0,
int  range = -1 
) const
override

◆ printDOFWithElapsedTime()

template<class DataTypes >
unsigned sofa::component::statecontainer::MechanicalObject< DataTypes >::printDOFWithElapsedTime ( core::ConstVecId  v,
unsigned  count = 0,
unsigned  time = 0,
std::ostream &  out = std::cerr 
)
override

◆ read() [1/3]

template<class DataTypes >
const Data< typename MechanicalObject< DataTypes >::MatrixDeriv > * sofa::component::statecontainer::MechanicalObject< DataTypes >::read ( core::ConstMatrixDerivId  v) const
override

◆ read() [2/3]

template<class DataTypes >
const Data< typename MechanicalObject< DataTypes >::VecCoord > * sofa::component::statecontainer::MechanicalObject< DataTypes >::read ( core::ConstVecCoordId  v) const
override

◆ read() [3/3]

template<class DataTypes >
const Data< typename MechanicalObject< DataTypes >::VecDeriv > * sofa::component::statecontainer::MechanicalObject< DataTypes >::read ( core::ConstVecDerivId  v) const
override

◆ readVec()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::readVec ( core::VecId  v,
std::istream &  in 
)
override

◆ reinit()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::reinit
override

◆ renumberValues()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::renumberValues ( const sofa::type::vector< sofa::Index > &  index)

Reorder values according to parameter.

Result of this method is : newValue[ i ] = oldValue[ index[i] ];

◆ replaceValue()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::replaceValue ( const sofa::Index  inputIndex,
const sofa::Index  outputIndex 
)

Overwrite values at index outputIndex by the ones at inputIndex.

◆ reserve()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::reserve ( Size  vsize)
virtual

◆ reset()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::reset
override

◆ resetAcc()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::resetAcc ( const core::ExecParams params,
core::VecDerivId  a = core::VecDerivId::dx() 
)
override

◆ resetConstraint()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::resetConstraint ( const core::ConstraintParams cparams)
override

◆ resetForce()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::resetForce ( const core::ExecParams params,
core::VecDerivId  f = core::VecDerivId::force() 
)
override

◆ resize()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::resize ( Size  vsize)
override

◆ setRotation()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::setRotation ( SReal  rx,
SReal  ry,
SReal  rz 
)
inline

◆ setScale()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::setScale ( SReal  sx,
SReal  sy,
SReal  sz 
)
inline

◆ setTranslation()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::setTranslation ( SReal  dx,
SReal  dy,
SReal  dz 
)
inline

◆ setVecCoord()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::setVecCoord ( core::ConstVecCoordId  vecId,
Data< VecCoord > *  v 
)
protected

Inserts VecCoord DOF coordinates vector at index in the vectorsCoord container.

◆ setVecDeriv()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::setVecDeriv ( core::ConstVecDerivId  vecId,
Data< VecDeriv > *  v 
)
protected

Inserts VecDeriv DOF derivates vector at index in the vectorsDeriv container.

◆ setVecIdProperties()

template<class DataTypes >
template<core::VecType vtype, core::VecAccess vaccess>
void sofa::component::statecontainer::MechanicalObject< DataTypes >::setVecIdProperties ( core::TVecId< vtype, vaccess >  v,
const core::VecIdProperties properties,
core::BaseData vec_d 
)
staticprotected

◆ setVecMatrixDeriv()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::setVecMatrixDeriv ( core::ConstMatrixDerivId  vecId,
Data< MatrixDeriv > *  m 
)
protected

Inserts MatrixDeriv DOF at index in the MatrixDeriv container.

◆ SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER() [1/2]

template<class DataTypes >
sofa::component::statecontainer::MechanicalObject< DataTypes >::SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER ( Index  ,
sofa::Index   
)

◆ SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER() [2/2]

template<class DataTypes >
sofa::component::statecontainer::MechanicalObject< DataTypes >::SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER ( Vector3  ,
sofa::type::Vec3   
)

◆ SOFA_CLASS()

template<class DataTypes >
sofa::component::statecontainer::MechanicalObject< DataTypes >::SOFA_CLASS ( SOFA_TEMPLATE(MechanicalObject< DataTypes >, DataTypes ,
SOFA_TEMPLATE(sofa::core::behavior::MechanicalState, DataTypes  
)

◆ storeResetState()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::storeResetState
override

◆ swapValues()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::swapValues ( const sofa::Index  idx1,
const sofa::Index  idx2 
)

Exchange values at indices idx1 and idx2.

◆ vAlloc() [1/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vAlloc ( const core::ExecParams params,
core::VecCoordId  v,
const core::VecIdProperties properties = {} 
)
override

Increment the index of the given MatrixDerivId, so that all 'allocated' vectors in this state have a lower index.

Allocate a new temporary vector

◆ vAlloc() [2/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vAlloc ( const core::ExecParams params,
core::VecDerivId  v,
const core::VecIdProperties properties = {} 
)
override

Allocate a new temporary vector.

◆ vAllocImpl()

template<class DataTypes >
template<core::VecType vtype>
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vAllocImpl ( core::TVecId< vtype, core::V_WRITE v,
const core::VecIdProperties properties 
)
protected

Generic implementation of the method vAlloc.

◆ vAvail() [1/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vAvail ( const core::ExecParams params,
core::VecCoordId v 
)
override

Increment the index of the given VecCoordId, so that all 'allocated' vectors in this state have a lower index.

◆ vAvail() [2/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vAvail ( const core::ExecParams params,
core::VecDerivId v 
)
override

Increment the index of the given VecDerivId, so that all 'allocated' vectors in this state have a lower index.

◆ vAvailImpl()

template<class DataTypes >
template<core::VecType vtype>
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vAvailImpl ( core::TVecId< vtype, core::V_WRITE > &  v,
sofa::type::vector< Data< core::StateVecType_t< DataTypes, vtype > > * > &  dataContainer 
)
protected

Generic implementation of the method vAvail.

◆ vDot()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::vDot ( const core::ExecParams params,
core::ConstVecId  a,
core::ConstVecId  b 
)
override

◆ vFree() [1/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vFree ( const core::ExecParams params,
core::VecCoordId  v 
)
override

Free a temporary vector.

◆ vFree() [2/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vFree ( const core::ExecParams params,
core::VecDerivId  v 
)
override

Free a temporary vector.

◆ vFreeImpl()

template<class DataTypes >
template<core::VecType vtype>
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vFreeImpl ( core::TVecId< vtype, core::V_WRITE v)
protected

Generic implementation of the method vFree.

◆ vInit() [1/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vInit ( const core::ExecParams params,
core::VecCoordId  v,
core::ConstVecCoordId  vSrc 
)
override

Free a temporary vector.

Initialize an unset vector

◆ vInit() [2/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vInit ( const core::ExecParams params,
core::VecDerivId  v,
core::ConstVecDerivId  vSrc 
)
override

Initialize an unset vector.

◆ vInitImpl()

template<class DataTypes >
template<core::VecType vtype>
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vInitImpl ( const core::ExecParams params,
core::TVecId< vtype, core::V_WRITE vId,
core::TVecId< vtype, core::V_READ vSrcId 
)
protected

Generic implementation of the method vInit.

◆ vMax()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::vMax ( const core::ExecParams params,
core::ConstVecId  a 
)
override

Maximum of the absolute values of the entries of state vector a. This is used to compute the infinite-norm of the vector.

◆ vMultiOp()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vMultiOp ( const core::ExecParams params,
const VMultiOp ops 
)
override

◆ vOp()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vOp ( const core::ExecParams params,
core::VecId  v,
core::ConstVecId  a = core::ConstVecId::null(),
core::ConstVecId  b = core::ConstVecId::null(),
SReal  f = 1.0 
)
override

Initialize an unset vector.

◆ vRealloc() [1/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vRealloc ( const core::ExecParams params,
core::VecCoordId  v,
const core::VecIdProperties properties = {} 
)
override

Allocate a new temporary vector.

Reallocate a new temporary vector

◆ vRealloc() [2/2]

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vRealloc ( const core::ExecParams params,
core::VecDerivId  v,
const core::VecIdProperties properties = {} 
)
override

Reallocate a new temporary vector.

◆ vReallocImpl()

template<class DataTypes >
template<core::VecType vtype>
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vReallocImpl ( core::TVecId< vtype, core::V_WRITE v,
const core::VecIdProperties properties 
)
protected

Generic implementation of the method vRealloc.

◆ vSize()

template<class DataTypes >
Size sofa::component::statecontainer::MechanicalObject< DataTypes >::vSize ( const core::ExecParams params,
core::ConstVecId  v 
)
override

◆ vSum()

template<class DataTypes >
SReal sofa::component::statecontainer::MechanicalObject< DataTypes >::vSum ( const core::ExecParams params,
core::ConstVecId  a,
unsigned  l 
)
override

Sum of the entries of state vector a at the power of l>0. This is used to compute the l-norm of the vector.

◆ vThreshold()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::vThreshold ( core::VecId  a,
SReal  threshold 
)
override

◆ write() [1/3]

template<class DataTypes >
Data< typename MechanicalObject< DataTypes >::MatrixDeriv > * sofa::component::statecontainer::MechanicalObject< DataTypes >::write ( core::MatrixDerivId  v)
override

◆ write() [2/3]

template<class DataTypes >
Data< typename MechanicalObject< DataTypes >::VecCoord > * sofa::component::statecontainer::MechanicalObject< DataTypes >::write ( core::VecCoordId  v)
override

◆ write() [3/3]

template<class DataTypes >
Data< typename MechanicalObject< DataTypes >::VecDeriv > * sofa::component::statecontainer::MechanicalObject< DataTypes >::write ( core::VecDerivId  v)
override

◆ writeState()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::writeState ( std::ostream &  out)
override

◆ writeVec()

template<class DataTypes >
void sofa::component::statecontainer::MechanicalObject< DataTypes >::writeVec ( core::ConstVecId  v,
std::ostream &  out 
)
override

Related details

◆ MechanicalObjectInternalData< DataTypes >

template<class DataTypes >
friend class MechanicalObjectInternalData< DataTypes >
friend