#include <MechanicalObject.h>
This class can be overridden if needed for additionnal storage within template specializations. More...
This class can be overridden if needed for additionnal storage within template specializations.
MechanicalObject class.
Public Attributes | |
Data< VecCoord > | x |
position coordinates of the degrees of freedom More... | |
Data< VecDeriv > | v |
velocity coordinates of the degrees of freedom More... | |
Data< VecDeriv > | f |
force vector of the degrees of freedom More... | |
Data< VecCoord > | x0 |
rest position coordinates of the degrees of freedom More... | |
Data< VecDeriv > | externalForces |
externalForces vector of the degrees of freedom More... | |
Data< VecDeriv > | dx |
dx vector of the degrees of freedom More... | |
Data< VecCoord > | xfree |
free position coordinates of the degrees of freedom More... | |
Data< VecDeriv > | vfree |
free velocity coordinates of the degrees of freedom More... | |
Data< MatrixDeriv > | c |
constraints applied to the degrees of freedom More... | |
Data< MatrixDeriv > | m |
mappingJacobian applied to the degrees of freedom More... | |
Data< VecCoord > | reset_position |
reset position coordinates of the degrees of freedom More... | |
Data< VecDeriv > | reset_velocity |
reset velocity coordinates of the degrees of freedom More... | |
defaulttype::MapMapSparseMatrix< Deriv > | c2 |
Data< SReal > | restScale |
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< float > | showObjectScale |
Scale for object display. (default=0.1) More... | |
Data< bool > | showIndices |
Show indices. (default=false) More... | |
Data< float > | showIndicesScale |
Scale for indices display. (default=0.02) More... | |
Data< bool > | showVectors |
Show velocity. (default=false) More... | |
Data< float > | showVectorsScale |
Scale for vectors display. (default=0.0001) More... | |
Data< int > | drawMode |
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::RGBAColor > | d_color |
drawing color More... | |
Protected Attributes | |
Data< int > | d_size |
Size of the vectors. More... | |
SingleLink< MechanicalObject< DataTypes >, core::topology::BaseMeshTopology, BaseLink::FLAG_STRONGLINK|BaseLink::FLAG_STOREPATH > | l_topology |
Data< int > | f_reserve |
Size to reserve when creating vectors. (default=0) More... | |
bool | m_initialized |
MechanicalObjectInternalData< DataTypes > | data |
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::Vec3 > | translation |
Translation of the DOFs. More... | |
Data< type::Vec3 > | rotation |
Rotation of the DOFs. More... | |
Data< type::Vec3 > | scale |
Scale of the DOFs in 3 dimensions. More... | |
Data< type::Vec3 > | translation2 |
Translation of the DOFs, applied after the rest position has been computed. More... | |
Data< type::Vec3 > | rotation2 |
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) | |
MechanicalObject & | operator= (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< ConstraintBlock > | constraintBlocks (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... | |
Data< MatrixDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::c |
constraints applied to the degrees of freedom
defaulttype::MapMapSparseMatrix< Deriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::c2 |
Data< type::RGBAColor > sofa::component::statecontainer::MechanicalObject< DataTypes >::d_color |
drawing color
|
protected |
Size of the vectors.
Data< bool > sofa::component::statecontainer::MechanicalObject< DataTypes >::d_useTopology |
Shall this object rely on any active topology to initialize its size and positions.
|
protected |
Given the number of a constraint Equation, find the index in the MatrixDeriv C, where the constraint is actually stored.
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)
Data< VecDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::dx |
dx vector of the degrees of freedom
Data< VecDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::externalForces |
externalForces vector of the degrees of freedom
Data< VecDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::f |
force vector of the degrees of freedom
|
protected |
Size to reserve when creating vectors. (default=0)
Data< MatrixDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::m |
mappingJacobian applied to the degrees of freedom
|
protected |
|
protected |
|
protected |
Data< VecCoord > sofa::component::statecontainer::MechanicalObject< DataTypes >::reset_position |
reset position coordinates of the degrees of freedom
Data< VecDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::reset_velocity |
reset velocity coordinates of the degrees of freedom
Data< SReal > sofa::component::statecontainer::MechanicalObject< DataTypes >::restScale |
optional scaling of rest position coordinates (to simulated pre-existing internal tension).(default = 1.0)
|
protected |
Rotation of the DOFs.
|
protected |
Rotation of the DOFs, applied the after the rest position has been computed.
|
protected |
Scale of the DOFs in 3 dimensions.
Data< bool > sofa::component::statecontainer::MechanicalObject< DataTypes >::showIndices |
Show indices. (default=false)
Data< float > sofa::component::statecontainer::MechanicalObject< DataTypes >::showIndicesScale |
Scale for indices display. (default=0.02)
Data< bool > sofa::component::statecontainer::MechanicalObject< DataTypes >::showObject |
Show objects. (default=false)
Data< float > sofa::component::statecontainer::MechanicalObject< DataTypes >::showObjectScale |
Scale for object display. (default=0.1)
Data< bool > sofa::component::statecontainer::MechanicalObject< DataTypes >::showVectors |
Show velocity. (default=false)
Data< float > sofa::component::statecontainer::MechanicalObject< DataTypes >::showVectorsScale |
Scale for vectors display. (default=0.0001)
|
protected |
Translation of the DOFs.
|
protected |
Translation of the DOFs, applied after the rest position has been computed.
Data< VecDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::v |
velocity coordinates of the degrees of freedom
|
protected |
Coordinates DOFs vectors table (static and dynamic allocated)
|
protected |
Derivates DOFs vectors table (static and dynamic allocated)
|
protected |
Constraint vectors table.
Data< VecDeriv > sofa::component::statecontainer::MechanicalObject< DataTypes >::vfree |
free velocity coordinates of the degrees of freedom
Data< VecCoord > sofa::component::statecontainer::MechanicalObject< DataTypes >::x |
position coordinates of the degrees of freedom
Data< VecCoord > sofa::component::statecontainer::MechanicalObject< DataTypes >::x0 |
rest position coordinates of the degrees of freedom
Data< VecCoord > sofa::component::statecontainer::MechanicalObject< DataTypes >::xfree |
free position coordinates of the degrees of freedom
|
protected |
|
protectedvirtual |
|
override |
|
override |
update the given bounding box, to include this
void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::addFromBaseVectorDifferentSize | ( | core::VecId | dest, |
const linearalgebra::BaseVector * | src, | ||
unsigned int & | offset | ||
) |
SOFA_COMPONENT_STATECONTAINER_API void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::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)
offset | the 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. |
void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::addFromBaseVectorSameSize | ( | core::VecId | dest, |
const linearalgebra::BaseVector * | src, | ||
unsigned int & | offset | ||
) |
SOFA_COMPONENT_STATECONTAINER_API void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::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)
offset | the 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 |
|
override |
Add data to a global BaseVector from the state stored in a local vector
offset | the 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 |
|
override |
Rotation using Euler Angles in degree.
void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::applyRotation | ( | const type::Quat< SReal > | q | ) |
SOFA_COMPONENT_STATECONTAINER_API void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::applyRotation | ( | const type::Quat< SReal > | q | ) |
|
override |
|
override |
|
override |
Apply translation vector to the position.
|
override |
|
override |
|
override |
|
override |
Bounding Box computation method.
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
|
overridevirtual |
Express the matrix L in term of block of matrices, using the indices of the lines in the MatrixDeriv container.
|
override |
Copy data to a local vector the state stored in a global BaseVector
offset | the 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 |
|
override |
Copy data to a global BaseMatrix from the state stored in a local vector.
|
override |
Copy data to a global BaseVector the state stored in a local vector
offset | the 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 |
void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::draw | ( | const core::visual::VisualParams * | vparams | ) |
SOFA_COMPONENT_STATECONTAINER_API void sofa::component::statecontainer::MechanicalObject< defaulttype::Rigid3Types >::draw | ( | const core::visual::VisualParams * | vparams | ) |
|
inlineoverride |
|
inlineprotected |
Internal function : Draw indices in 3d coordinates.
|
inlineprotected |
Internal function : Draw vectors.
|
override |
|
override |
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)
|
override |
|
override |
|
override |
Get the indices of the particles located in the given bounding box.
|
inlineoverride |
|
inlineoverride |
|
inlineoverride |
|
protected |
Shortcut to get a read accessor corresponding to the provided VecType from a VecId.
|
inlinevirtual |
|
inlineoverride |
|
inlineoverride |
|
inlinevirtual |
|
inline |
|
inline |
|
inline |
|
protected |
Shortcut to get a write accessor corresponding to the provided VecType from a VecId.
|
protected |
Shortcut to get a write-only accessor corresponding to the provided VecType from a VecId.
|
override |
|
override |
|
override |
bool sofa::component::statecontainer::MechanicalObject< DataTypes >::isIndependent |
if this mechanical object stores independent dofs (in opposition to mapped dofs)
MechanicalObject< DataTypes > & sofa::component::statecontainer::MechanicalObject< DataTypes >::operator= | ( | const MechanicalObject< DataTypes > & | obj | ) |
|
override |
|
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
|
override |
|
override |
|
override |
|
override |
|
override |
|
override |
|
override |
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] ];
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.
|
virtual |
|
override |
|
override |
|
override |
|
override |
|
override |
|
inline |
|
inline |
|
inline |
|
protected |
Inserts VecCoord DOF coordinates vector at index in the vectorsCoord container.
|
protected |
Inserts VecDeriv DOF derivates vector at index in the vectorsDeriv container.
|
staticprotected |
|
protected |
Inserts MatrixDeriv DOF at index in the MatrixDeriv container.
sofa::component::statecontainer::MechanicalObject< DataTypes >::SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER | ( | Index | , |
sofa::Index | |||
) |
sofa::component::statecontainer::MechanicalObject< DataTypes >::SOFA_ATTRIBUTE_REPLACED__TYPEMEMBER | ( | Vector3 | , |
sofa::type::Vec3 | |||
) |
sofa::component::statecontainer::MechanicalObject< DataTypes >::SOFA_CLASS | ( | SOFA_TEMPLATE(MechanicalObject< DataTypes >, DataTypes) | , |
SOFA_TEMPLATE(sofa::core::behavior::MechanicalState, DataTypes) | |||
) |
|
override |
void sofa::component::statecontainer::MechanicalObject< DataTypes >::swapValues | ( | const sofa::Index | idx1, |
const sofa::Index | idx2 | ||
) |
Exchange values at indices idx1 and idx2.
|
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
|
override |
Allocate a new temporary vector.
|
protected |
Generic implementation of the method vAlloc.
|
override |
Increment the index of the given VecCoordId, so that all 'allocated' vectors in this state have a lower index.
|
override |
Increment the index of the given VecDerivId, so that all 'allocated' vectors in this state have a lower index.
|
protected |
Generic implementation of the method vAvail.
|
override |
|
override |
Free a temporary vector.
|
override |
Free a temporary vector.
|
protected |
Generic implementation of the method vFree.
|
override |
Free a temporary vector.
Initialize an unset vector
|
override |
Initialize an unset vector.
|
protected |
Generic implementation of the method vInit.
|
override |
Maximum of the absolute values of the entries of state vector a. This is used to compute the infinite-norm of the vector.
|
override |
|
override |
Initialize an unset vector.
|
override |
Allocate a new temporary vector.
Reallocate a new temporary vector
|
override |
Reallocate a new temporary vector.
|
protected |
Generic implementation of the method vRealloc.
|
override |
|
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.
|
override |
|
override |
|
override |
|
override |
|
override |
|
override |
|
friend |