diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index fe937ef..2a99086 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -74,19 +74,11 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping typedef TIn2 In2; typedef TOut Out; - // TODO(dmarchal:2024/06/07) This very long list of public typedefs looks - // questionnable at least this has to be justified by comment on why these - // typedefs are public - typedef typename In1::Coord Coord1; - typedef typename In1::Deriv Deriv1; + using Coord1 = sofa::Coord_t; + using Deriv1 = sofa::Deriv_t; - typedef typename In2::Coord Coord2; - typedef typename In2::Deriv Deriv2; + using OutCoord = sofa::Coord_t; - typedef typename Out::Coord OutCoord; - typedef typename Out::Deriv OutDeriv; - -public: // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this // really needed ? diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index 554bb99..93ba2b3 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -33,17 +33,17 @@ using namespace sofa::defaulttype; template <> void DiscreteCosseratMapping:: applyJ( - const sofa::core::MechanicalParams* /* mparams */, const vector< OutDataVecDeriv*>& dataVecOutVel, - const vector& dataVecIn1Vel, - const vector& dataVecIn2Vel) { + const sofa::core::MechanicalParams* /* mparams */, const vector< sofa::DataVecDeriv_t*>& dataVecOutVel, + const vector*>& dataVecIn1Vel, + const vector*>& dataVecIn2Vel) { if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) return; msg_info() << " ########## ApplyJ R Function ########"; - const In1VecDeriv& in1_vel = sofa::helper::getReadAccessor(*dataVecIn1Vel[0]); - const In2VecDeriv& in2_vel = sofa::helper::getReadAccessor(*dataVecIn2Vel[0]); + const sofa::VecDeriv_t& in1_vel = sofa::helper::getReadAccessor(*dataVecIn1Vel[0]); + const sofa::VecDeriv_t& in2_vel = sofa::helper::getReadAccessor(*dataVecIn2Vel[0]); auto out_vel = sofa::helper::getWriteOnlyAccessor(*dataVecOutVel[0]); @@ -67,7 +67,7 @@ void DiscreteCosseratMapping:: applyJ( baseVelocity[u] = in2_vel[baseIndex][u]; //Apply the local transform i.e. from SOFA's frame to Cosserat's frame - const In2VecCoord& xfrom2Data = sofa::helper::getReadAccessor(*m_fromModel2->read(sofa::core::ConstVecCoordId::position())); + const sofa::VecCoord_t& xfrom2Data = sofa::helper::getReadAccessor(*m_fromModel2->read(sofa::core::ConstVecCoordId::position())); Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()).inversed(); Mat6x6 P = this->buildProjector(TInverse); Vec6 baseLocalVelocity = P * baseVelocity; //This is the base velocity in Locale frame @@ -90,7 +90,7 @@ void DiscreteCosseratMapping:: applyJ( m_nodesVelocityVectors.push_back(eta_node_i); msg_info() << "Node velocity : "<< i << " = " << eta_node_i; } - const OutVecCoord& out = sofa::helper::getReadAccessor(*m_toModel->read(sofa::core::ConstVecCoordId::position())); + const sofa::VecCoord_t& out = sofa::helper::getReadAccessor(*m_toModel->read(sofa::core::ConstVecCoordId::position())); auto sz = curv_abs_frames.size(); out_vel.resize(sz); @@ -112,23 +112,23 @@ void DiscreteCosseratMapping:: applyJ( template <> void DiscreteCosseratMapping:: applyJT( - const sofa::core::MechanicalParams* /*mparams*/, const vector< In1DataVecDeriv*>& dataVecOut1Force, - const vector< In2DataVecDeriv*>& dataVecOut2Force, - const vector& dataVecInForce) { + const sofa::core::MechanicalParams* /*mparams*/, const vector< sofa::DataVecDeriv_t*>& dataVecOut1Force, + const vector< sofa::DataVecDeriv_t*>& dataVecOut2Force, + const vector*>& dataVecInForce) { if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) return; msg_info() << " ########## ApplyJT force R Function ########"; - const OutVecDeriv& in = dataVecInForce[0]->getValue(); + const sofa::VecDeriv_t& in = dataVecInForce[0]->getValue(); - In1VecDeriv out1 = sofa::helper::getWriteAccessor(*dataVecOut1Force[0]); - In2VecDeriv out2 = sofa::helper::getWriteAccessor(*dataVecOut2Force[0]); + sofa::VecDeriv_t out1 = sofa::helper::getWriteAccessor(*dataVecOut1Force[0]); + sofa::VecDeriv_t out2 = sofa::helper::getWriteAccessor(*dataVecOut2Force[0]); const auto baseIndex = d_baseIndex.getValue(); - const OutVecCoord& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); + const sofa::VecCoord_t& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const sofa::DataVecCoord_t* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const sofa::VecCoord_t x1from = x1fromData->getValue(); vector local_F_Vec; local_F_Vec.clear(); out1.resize(x1from.size()); @@ -195,9 +195,9 @@ void DiscreteCosseratMapping:: applyJT( template <> void DiscreteCosseratMapping::applyJT( - const sofa::core::ConstraintParams*/*cparams*/ , const vector< In1DataMatrixDeriv*>& dataMatOut1Const, - const vector< In2DataMatrixDeriv*>& dataMatOut2Const , - const vector& dataMatInConst) + const sofa::core::ConstraintParams*/*cparams*/ , const vector< sofa::DataMatrixDeriv_t*>& dataMatOut1Const, + const vector< sofa::DataMatrixDeriv_t*>& dataMatOut2Const , + const vector*>& dataMatInConst) { if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) return; @@ -205,13 +205,13 @@ void DiscreteCosseratMapping::applyJT( msg_info() << " ########## ApplyJT constraint R Function ########"; //We need only one input In model and input Root model (if present) - In1MatrixDeriv& out1 = sofa::helper::getWriteAccessor(*dataMatOut1Const[0]); // constraints on the strain space (reduced coordinate) - In2MatrixDeriv& out2 = sofa::helper::getWriteAccessor(*dataMatOut2Const[0]); // constraints on the reference frame (base frame) - const OutMatrixDeriv& in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped frames + sofa::MatrixDeriv_t& out1 = sofa::helper::getWriteAccessor(*dataMatOut1Const[0]); // constraints on the strain space (reduced coordinate) + sofa::MatrixDeriv_t& out2 = sofa::helper::getWriteAccessor(*dataMatOut2Const[0]); // constraints on the reference frame (base frame) + const sofa::MatrixDeriv_t& in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped frames - const OutVecCoord& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); + const sofa::VecCoord_t& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const sofa::DataVecCoord_t* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const sofa::VecCoord_t x1from = x1fromData->getValue(); TangentTransform matB_trans; matB_trans.clear(); for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; @@ -219,10 +219,10 @@ void DiscreteCosseratMapping::applyJT( vector< std::tuple > NodesInvolved; vector< std::tuple > NodesInvolvedCompressed; - typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); + typename sofa::MatrixDeriv_t::RowConstIterator rowItEnd = in.end(); bool doPrintLog = f_printLog.getValue(); - for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) + for (typename sofa::MatrixDeriv_t::RowConstIterator rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) { msg_info_when(doPrintLog) <<"************* Apply JT (MatrixDeriv) iteration on line " @@ -239,8 +239,8 @@ void DiscreteCosseratMapping::applyJT( <<"no column for this constraint"; continue; } - typename In1MatrixDeriv::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number - typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); + typename sofa::MatrixDeriv_t::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number + typename sofa::MatrixDeriv_t::RowIterator o2 = out2.writeLine(rowIt.index()); NodesInvolved.clear(); while (colIt != colItEnd) diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index bffa5d8..2658233 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -56,29 +56,6 @@ class DiscreteCosseratMapping : public BaseCosseratMapping { typedef TIn2 In2; typedef TOut Out; - using typename Inherit1::In1VecCoord; - using typename Inherit1::In1VecDeriv; - using typename Inherit1::In1MatrixDeriv; - using typename Inherit1::In1DataVecCoord; - using typename Inherit1::In1DataVecDeriv; - using typename Inherit1::In1DataMatrixDeriv; - - using typename Inherit1::In2VecCoord; - using typename Inherit1::In2VecDeriv; - using typename Inherit1::In2MatrixDeriv; - using typename Inherit1::In2DataVecCoord; - using typename Inherit1::In2DataVecDeriv; - using typename Inherit1::In2DataMatrixDeriv; - - using typename Inherit1::OutCoord; - using typename Inherit1::OutDeriv; - using typename Inherit1::OutVecCoord; - using typename Inherit1::OutVecDeriv; - using typename Inherit1::OutMatrixDeriv; - using typename Inherit1::OutDataVecCoord; - using typename Inherit1::OutDataVecDeriv; - using typename Inherit1::OutDataMatrixDeriv; - ////////////////////////////////////////////////////////////////////// /// @name Data Fields /// @{ @@ -106,20 +83,21 @@ class DiscreteCosseratMapping : public BaseCosseratMapping { ////////////////////////////////////////////////////////////////////// /// The following method are inherited from MultiMapping /// @{ - void apply(const sofa::core::MechanicalParams * /* mparams */, - const vector &dataVecOutPos, - const vector &dataVecIn1Pos, - const vector &dataVecIn2Pos) override; + auto apply(const sofa::core::MechanicalParams* /* mparams */, + const vector*>& dataVecOutPos, + const vector*>& dataVecIn1Pos, + const vector*>& dataVecIn2Pos) -> + void override; void applyJ(const sofa::core::MechanicalParams * /* mparams */, - const vector &dataVecOutVel, - const vector &dataVecIn1Vel, - const vector &dataVecIn2Vel) override; + const vector *> &dataVecOutVel, + const vector *> &dataVecIn1Vel, + const vector *> &dataVecIn2Vel) override; void applyJT(const sofa::core::MechanicalParams * /* mparams */, - const vector &dataVecOut1Force, - const vector &dataVecOut2RootForce, - const vector &dataVecInForce) override; + const vector *> &dataVecOut1Force, + const vector *> &dataVecOut2RootForce, + const vector *> &dataVecInForce) override; // TODO(dmarchal:2024/06/13): Override with an empty function is a rare code pattern // to make it clear this is the intented and not just an "I'm too lazy to implement it" @@ -131,9 +109,9 @@ class DiscreteCosseratMapping : public BaseCosseratMapping { /// Support for constraints. void applyJT( const sofa::core::ConstraintParams *cparams, - const vector &dataMatOut1Const, - const vector &dataMatOut2Const, - const vector &dataMatInConst) override; + const vector *> &dataMatOut1Const, + const vector *> &dataMatOut2Const, + const vector *> &dataMatInConst) override; /// @} ///////////////////////////////////////////////////////////////////////////// diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index d671f0f..3f815b7 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -76,7 +76,7 @@ DiscreteCosseratMapping::DiscreteCosseratMapping() [this](const sofa::core::DataTracker &t) { SOFA_UNUSED(t); this->initializeFrames(); - const In1VecCoord &inDeform = + const sofa::VecCoord_t &inDeform = m_fromModel1->read(sofa::core::ConstVecCoordId::position())->getValue(); this->updateExponentialSE3(inDeform); return sofa::core::objectmodel::ComponentState::Valid; @@ -93,9 +93,9 @@ void DiscreteCosseratMapping::doBaseCosseratInit() { template void DiscreteCosseratMapping::apply( const sofa::core::MechanicalParams * /* mparams */, - const vector &dataVecOutPos, - const vector &dataVecIn1Pos, - const vector &dataVecIn2Pos) { + const vector *> &dataVecOutPos, + const vector *> &dataVecIn1Pos, + const vector *> &dataVecIn2Pos) { if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) return; @@ -106,11 +106,11 @@ void DiscreteCosseratMapping::apply( return; /// Do Apply // We need only one input In model and input Root model (if present) - const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); - const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); + const sofa::VecCoord_t &in1 = dataVecIn1Pos[0]->getValue(); + const sofa::VecCoord_t &in2 = dataVecIn2Pos[0]->getValue(); const auto sz = d_curv_abs_frames.getValue().size(); - OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); // frames states + sofa::VecCoord_t &out = *dataVecOutPos[0]->beginEdit(); // frames states out.resize(sz); const auto baseIndex = d_baseIndex.getValue(); @@ -141,7 +141,7 @@ void DiscreteCosseratMapping::apply( Vec3 origin = frame.getOrigin(); Quat orientation = frame.getOrientation(); - out[i] = OutCoord(origin, orientation); + out[i] = sofa::Coord_t(origin, orientation); } // If the printLog attribute is checked then print distance between out @@ -197,9 +197,9 @@ void DiscreteCosseratMapping::computeLogarithm( template void DiscreteCosseratMapping::applyJ( const sofa::core::MechanicalParams * /* mparams */, - const vector &dataVecOutVel, - const vector &dataVecIn1Vel, - const vector &dataVecIn2Vel) { + const vector *> &dataVecOutVel, + const vector *> &dataVecIn1Vel, + const vector *> &dataVecIn2Vel) { if (dataVecOutVel.empty() || dataVecIn1Vel.empty() || dataVecIn2Vel.empty()) return; @@ -208,9 +208,9 @@ void DiscreteCosseratMapping::applyJ( return; if (d_debug.getValue()) std::cout << " ########## ApplyJ Function ########" << std::endl; - const In1VecDeriv &in1_vel = dataVecIn1Vel[0]->getValue(); - const In2VecDeriv &in2_vel = dataVecIn2Vel[0]->getValue(); - OutVecDeriv &out_vel = *dataVecOutVel[0]->beginEdit(); + const sofa::VecDeriv_t &in1_vel = dataVecIn1Vel[0]->getValue(); + const sofa::VecDeriv_t &in2_vel = dataVecIn2Vel[0]->getValue(); + sofa::VecDeriv_t &out_vel = *dataVecOutVel[0]->beginEdit(); const auto baseIndex = d_baseIndex.getValue(); // Curv abscissa of nodes and frames @@ -219,7 +219,7 @@ void DiscreteCosseratMapping::applyJ( sofa::helper::ReadAccessor>> curv_abs_frames = d_curv_abs_frames; - const In1VecCoord &inDeform = + const sofa::VecDeriv_t &inDeform = m_fromModel1->read(sofa::core::ConstVecCoordId::position()) ->getValue(); // Strains // Compute the tangent Exponential SE3 vectors @@ -234,7 +234,7 @@ void DiscreteCosseratMapping::applyJ( baseVelocity[u] = in2_vel[baseIndex][u]; // Apply the local transform i.e. from SOFA's frame to Cosserat's frame - const In2VecCoord &xfrom2Data = + const sofa::VecCoord_t &xfrom2Data = m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()) @@ -263,7 +263,7 @@ void DiscreteCosseratMapping::applyJ( std::cout << "Node velocity : " << i << " = " << eta_node_i << std::endl; } - const OutVecCoord &out = + const sofa::VecCoord_t &out = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); auto sz = curv_abs_frames.size(); out_vel.resize(sz); @@ -299,9 +299,9 @@ void DiscreteCosseratMapping::applyJ( template void DiscreteCosseratMapping::applyJT( const sofa::core::MechanicalParams * /*mparams*/, - const vector &dataVecOut1Force, - const vector &dataVecOut2Force, - const vector &dataVecInForce) { + const vector *> &dataVecOut1Force, + const vector *> &dataVecOut2Force, + const vector *> &dataVecInForce) { if (dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) @@ -312,17 +312,17 @@ void DiscreteCosseratMapping::applyJT( if (d_debug.getValue()) std::cout << " ########## ApplyJT force Function ########" << std::endl; - const OutVecDeriv &in = dataVecInForce[0]->getValue(); + const sofa::VecDeriv_t &in = dataVecInForce[0]->getValue(); - In1VecDeriv &out1 = *dataVecOut1Force[0]->beginEdit(); - In2VecDeriv &out2 = *dataVecOut2Force[0]->beginEdit(); + sofa::VecDeriv_t &out1 = *dataVecOut1Force[0]->beginEdit(); + sofa::VecDeriv_t &out2 = *dataVecOut2Force[0]->beginEdit(); const auto baseIndex = d_baseIndex.getValue(); - const OutVecCoord &frame = + const sofa::VecCoord_t &frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord *x1fromData = + const sofa::DataVecCoord_t *x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); + const sofa::VecCoord_t x1from = x1fromData->getValue(); vector local_F_Vec; local_F_Vec.clear(); @@ -409,9 +409,9 @@ void DiscreteCosseratMapping::applyJT( template void DiscreteCosseratMapping::applyJT( const sofa::core::ConstraintParams * /*cparams*/, - const vector &dataMatOut1Const, - const vector &dataMatOut2Const, - const vector &dataMatInConst) { + const vector *> &dataMatOut1Const, + const vector *> &dataMatOut2Const, + const vector *> &dataMatInConst) { if (dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty()) return; @@ -423,21 +423,21 @@ void DiscreteCosseratMapping::applyJT( std::cout << " ########## ApplyJT Constraint Function ########" << std::endl; // We need only one input In model and input Root model (if present) - In1MatrixDeriv &out1 = + sofa::MatrixDeriv_t &out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space // (reduced coordinate) - In2MatrixDeriv &out2 = + sofa::MatrixDeriv_t &out2 = *dataMatOut2Const[0] ->beginEdit(); // constraints on the reference frame (base frame) - const OutMatrixDeriv &in = + const sofa::MatrixDeriv_t &in = dataMatInConst[0] ->getValue(); // input constraints defined on the mapped frames - const OutVecCoord &frame = + const sofa::VecCoord_t &frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord *x1fromData = + const sofa::DataVecCoord_t *x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); + const sofa::VecCoord_t x1from = x1fromData->getValue(); Mat3x6 matB_trans; matB_trans.clear(); @@ -448,17 +448,17 @@ void DiscreteCosseratMapping::applyJT( vector> NodesInvolvedCompressed; // helper::vector NodesConstraintDirection; - typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); + typename sofa::MatrixDeriv_t::RowConstIterator rowItEnd = in.end(); - for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); + for (typename sofa::MatrixDeriv_t::RowConstIterator rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) { if (d_debug.getValue()) { std::cout << "************* Apply JT (MatrixDeriv) iteration on line "; std::cout << rowIt.index(); std::cout << "************* " << std::endl; } - typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); - typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); + typename sofa::MatrixDeriv_t::ColConstIterator colIt = rowIt.begin(); + typename sofa::MatrixDeriv_t::ColConstIterator colItEnd = rowIt.end(); // Creates a constraints if the input constraint is not empty. if (colIt == colItEnd) { @@ -467,15 +467,15 @@ void DiscreteCosseratMapping::applyJT( } continue; } - typename In1MatrixDeriv::RowIterator o1 = + typename sofa::MatrixDeriv_t::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number - typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); + typename sofa::MatrixDeriv_t::RowIterator o2 = out2.writeLine(rowIt.index()); NodesInvolved.clear(); while (colIt != colItEnd) { int childIndex = colIt.index(); - const OutDeriv valueConst_ = colIt.val(); + const sofa::Deriv_t valueConst_ = colIt.val(); Vec6 valueConst; for (unsigned j = 0; j < 6; j++) valueConst[j] = valueConst_[j]; @@ -600,7 +600,7 @@ void DiscreteCosseratMapping::applyJT( template void DiscreteCosseratMapping::computeBBox( const sofa::core::ExecParams *, bool) { - const OutVecCoord &x = + const sofa::VecCoord_t &x = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); SReal minBBox[3] = {std::numeric_limits::max(), @@ -610,7 +610,7 @@ void DiscreteCosseratMapping::computeBBox( -std::numeric_limits::max(), -std::numeric_limits::max()}; for (std::size_t i = 0; i < x.size(); i++) { - const OutCoord &p = x[i]; + const sofa::Coord_t &p = x[i]; for (int c = 0; c < 3; c++) { if (p[c] > maxBBox[c]) maxBBox[c] = p[c]; @@ -632,9 +632,9 @@ void DiscreteCosseratMapping::draw( const auto stateLifeCycle = vparams->drawTool()->makeStateLifeCycle(); - const OutDataVecCoord *xfromData = + const sofa::DataVecCoord_t *xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); - const OutVecCoord xData = xfromData->getValue(); + const sofa::VecCoord_t xData = xfromData->getValue(); vector positions; vector> Orientation; positions.clear(); @@ -646,9 +646,9 @@ void DiscreteCosseratMapping::draw( } // Get access articulated - const In1DataVecCoord *artiData = + const sofa::DataVecCoord_t *artiData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord xPos = artiData->getValue(); + const sofa::VecCoord_t xPos = artiData->getValue(); RGBAColor drawColor = d_color.getValue(); // draw each segment of the beam as a cylinder.