From fb2a3e33dd3b8b617a302158143133fd282b9a0c Mon Sep 17 00:00:00 2001 From: Hugo Date: Tue, 19 Mar 2024 16:01:02 +0100 Subject: [PATCH] Follow SOFA Lifecycle v24.06 (#102) --- src/Cosserat/constraint/CosseratActuatorConstraint.inl | 3 ++- .../constraint/CosseratNeedleSlidingConstraint.h | 10 ++++------ .../constraint/CosseratNeedleSlidingConstraint.inl | 5 +++-- src/Cosserat/constraint/QPSlidingConstraint.h | 2 +- src/Cosserat/constraint/QPSlidingConstraint.inl | 10 +++++----- src/Cosserat/engine/CosseratState.h | 2 +- src/Cosserat/engine/PointsManager.h | 4 ++-- src/Cosserat/engine/PointsManager.inl | 2 -- src/Cosserat/mapping/BaseCosserat.h | 2 +- src/Cosserat/mapping/DifferenceMultiMapping.inl | 2 +- src/Cosserat/mapping/DiscreteCosseratMapping.h | 2 +- src/Cosserat/mapping/DiscreteCosseratMapping.inl | 4 ++-- src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h | 2 +- .../mapping/DiscreteDynamicCosseratMapping.inl | 1 - src/Cosserat/mapping/LegendrePolynomialsMapping.h | 2 +- src/Cosserat/mapping/LegendrePolynomialsMapping.inl | 1 - src/Cosserat/mapping/RigidDistanceMapping.cpp | 2 +- src/Cosserat/mapping/RigidDistanceMapping.inl | 6 ++---- 18 files changed, 28 insertions(+), 34 deletions(-) diff --git a/src/Cosserat/constraint/CosseratActuatorConstraint.inl b/src/Cosserat/constraint/CosseratActuatorConstraint.inl index bf233508..8300c90a 100644 --- a/src/Cosserat/constraint/CosseratActuatorConstraint.inl +++ b/src/Cosserat/constraint/CosseratActuatorConstraint.inl @@ -83,7 +83,8 @@ void CosseratActuatorConstraint::internalInit() if(d_value.getValue().size()==0) { WriteAccessor>> value = d_value; - value.resize(1,0.); + value.resize(1); + value[0] = 0.; } // check for errors in the initialization diff --git a/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.h b/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.h index fef8e2d3..0f240906 100644 --- a/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.h +++ b/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.h @@ -109,13 +109,11 @@ namespace sofa::component::constraintset j.multTransposeBaseVector(res, lambda); // lambda is a vector of scalar value so block size is one. } - void storeLambda(const ConstraintParams */*cParams*/, MultiVecDerivId res, const sofa::linearalgebra::BaseVector *lambda) override + void storeLambda(const ConstraintParams *cParams, MultiVecDerivId res, const sofa::linearalgebra::BaseVector *lambda) override { - // if (cParams) - // { - // storeLambda(cParams, *res[m_state1->getMstate()].write(), *cParams->readJ(m_state1->getMstate()), lambda); - // storeLambda(cParams, *res[m_state2->getMstate()].write(), *cParams->readJ(m_state2->getMstate()), lambda); - // } + SOFA_UNUSED(cParams); + SOFA_UNUSED(res); + SOFA_UNUSED(lambda); } protected: diff --git a/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.inl b/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.inl index ef381495..022e8456 100644 --- a/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.inl +++ b/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.inl @@ -32,7 +32,7 @@ #include #include -#include +#include #include "CosseratNeedleSlidingConstraint.h" namespace sofa::component::constraintset @@ -91,7 +91,8 @@ namespace sofa::component::constraintset if (d_value.getValue().size() == 0) { WriteAccessor>> value = d_value; - value.resize(1, 0.); + value.resize(1); + value[0] = 0.; } // check for errors in the initialization diff --git a/src/Cosserat/constraint/QPSlidingConstraint.h b/src/Cosserat/constraint/QPSlidingConstraint.h index 9bb68ef0..31fa3bc3 100644 --- a/src/Cosserat/constraint/QPSlidingConstraint.h +++ b/src/Cosserat/constraint/QPSlidingConstraint.h @@ -35,7 +35,7 @@ #include #include -#include +#include namespace sofa::component::constraintset { diff --git a/src/Cosserat/constraint/QPSlidingConstraint.inl b/src/Cosserat/constraint/QPSlidingConstraint.inl index 3defedf8..11798e24 100644 --- a/src/Cosserat/constraint/QPSlidingConstraint.inl +++ b/src/Cosserat/constraint/QPSlidingConstraint.inl @@ -32,7 +32,7 @@ #include #include -#include +#include #include "QPSlidingConstraint.h" @@ -95,7 +95,8 @@ void QPSlidingConstraint::internalInit() if(d_value.getValue().size()==0) { WriteAccessor>> value = d_value; - value.resize(1,0.); + value.resize(1); + value[0] = 0.; } // check for errors in the initialization @@ -205,8 +206,7 @@ void QPSlidingConstraint::getConstraintResolution(const ConstraintPar unsigned int& offset) { ReadAccessor> positions = m_state->readPositions(); - // std::cout << "The position size is : " << positions.size()<< std::endl; - double imposedValue= 1.0; + for (size_t i = 0; i < positions.size(); i++){ resTab[offset++] = new BilateralConstraintResolution(); @@ -215,13 +215,13 @@ void QPSlidingConstraint::getConstraintResolution(const ConstraintPar resTab[offset++] = new BilateralConstraintResolution(); } } - // std::cout << "The position size is END " << std::endl; } template void QPSlidingConstraint::draw(const VisualParams* vparams) { + SOFA_UNUSED(vparams); if(d_componentState.getValue() != ComponentState::Valid) return ; diff --git a/src/Cosserat/engine/CosseratState.h b/src/Cosserat/engine/CosseratState.h index 9ade0c5d..ed424097 100644 --- a/src/Cosserat/engine/CosseratState.h +++ b/src/Cosserat/engine/CosseratState.h @@ -35,7 +35,7 @@ namespace sofa::component::container using namespace core::objectmodel; using namespace sofa::defaulttype; using namespace sofa::core::topology; - using sofa::defaulttype::Vector3; + using sofa::type::Vec3; template class TemperatureState : public sofa::component::container::MechanicalObject diff --git a/src/Cosserat/engine/PointsManager.h b/src/Cosserat/engine/PointsManager.h index 4ebcc49b..6d9f7353 100755 --- a/src/Cosserat/engine/PointsManager.h +++ b/src/Cosserat/engine/PointsManager.h @@ -43,8 +43,8 @@ namespace sofa::core::behavior PointSetTopologyModifier *m_modifier; core::behavior::MechanicalState *m_beam; - void init(); - void handleEvent(sofa::core::objectmodel::Event *event); + void init() override; + void handleEvent(sofa::core::objectmodel::Event *event) override; // void draw(const core::visual::VisualParams *vparams); void addNewPointToState(); diff --git a/src/Cosserat/engine/PointsManager.inl b/src/Cosserat/engine/PointsManager.inl index 0279c2e3..266955b3 100755 --- a/src/Cosserat/engine/PointsManager.inl +++ b/src/Cosserat/engine/PointsManager.inl @@ -76,10 +76,8 @@ namespace sofa::core::behavior { helper::WriteAccessor> x = *this->getMstate()->write(core::VecCoordId::position()); helper::WriteAccessor> xfree = *this->getMstate()->write(core::VecCoordId::freePosition()); - const helper::ReadAccessor> &beam = m_beam->readPositions(); unsigned nbPoints = this->getTopology()->getNbPoints(); // do not take the last point because there is a bug - size_t beamSz = beam.size(); sofa::type::vector Indices; if (nbPoints > 0) { diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 69c78d65..e9a532ec 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -38,7 +38,7 @@ using sofa::defaulttype::SolidTypes ; using sofa::core::objectmodel::BaseContext ; using sofa::type::Matrix3; using sofa::type::Matrix4; -using type::Vector3; +using type::Vec3; using type::Vec6; using std::get; using sofa::core::objectmodel::BaseObject; diff --git a/src/Cosserat/mapping/DifferenceMultiMapping.inl b/src/Cosserat/mapping/DifferenceMultiMapping.inl index cecbcfc4..c9540d2e 100644 --- a/src/Cosserat/mapping/DifferenceMultiMapping.inl +++ b/src/Cosserat/mapping/DifferenceMultiMapping.inl @@ -701,7 +701,7 @@ namespace sofa::component::mapping if (d_lastPointIsFixed.getValue()) { - if ((rowIt.index() / 2) < (x1from.size() - 1)) + if ((rowIt.index() / 2) < (int)(x1from.size() - 1)) { while (colIt != colItEnd) { diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index 58b2e5c3..aa2022df 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -108,7 +108,7 @@ class DiscreteCosseratMapping : public core::Multi2Mapping, pu Data d_min; Data d_radius ; Data d_drawMapBeam ; - Data d_color; + Data d_color; Data > d_index; Data d_baseIndex; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 8fb2ae2f..1635c9b1 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -60,7 +60,7 @@ DiscreteCosseratMapping::DiscreteCosseratMapping() "the axis in which we want to show the deformation.\n")) , d_drawMapBeam(initData(&d_drawMapBeam, true,"nonColored", "if this parameter is false, you draw the beam with " "color according to the force apply to each beam")) - , d_color(initData(&d_color, type::Vec4f (40/255.0, 104/255.0, 137/255.0, 0.8) ,"color", "The default beam color")) + , d_color(initData(&d_color, sofa::type::RGBAColor(40/255.0, 104/255.0, 137/255.0, 0.8) ,"color", "The default beam color")) , d_index(initData(&d_index, "index", "if this parameter is false, you draw the beam with color " "according to the force apply to each beam")) , d_baseIndex(initData(&d_baseIndex, (unsigned int) 0, "baseIndex", "This parameter defines the index of the rigid " @@ -588,7 +588,7 @@ void DiscreteCosseratMapping::draw(const core::visual::VisualP glLineWidth(d_radius.getValue()); glBegin(GL_LINES); if(d_drawMapBeam.getValue()){ - type::Vec4f _color = d_color.getValue(); + sofa::type::RGBAColor _color = d_color.getValue(); RGBAColor colorL = RGBAColor(_color[0],_color[1],_color[2],_color[3]); glColor4f(colorL[0], colorL[1], colorL[2],colorL[3]); for (unsigned int i=0; i::computeJ_Jdot_i(const Mat Mat6x6 M; Mat6x3 Si_dot; - Mat6x6 M_dot; Mat6x6 adj_eta; //to be computed //std::cout << "indice vector : "<< this->m_indicesVectors <<" vecId :"<< this->m_indicesVectors[frameId] << std::endl; //std::cout << "this->m_framesTangExpVectors[frameId] :"<< this->m_framesTangExpVectors[frameId] << std::endl; diff --git a/src/Cosserat/mapping/LegendrePolynomialsMapping.h b/src/Cosserat/mapping/LegendrePolynomialsMapping.h index 1dcd9672..4726bfbf 100644 --- a/src/Cosserat/mapping/LegendrePolynomialsMapping.h +++ b/src/Cosserat/mapping/LegendrePolynomialsMapping.h @@ -20,7 +20,7 @@ namespace sofa::component::mapping { using sofa::core::objectmodel::BaseContext; using sofa::type::Matrix3; using sofa::type::Matrix4; - using type::Vector3; + using type::Vec3; using type::Vec6; using std::get; diff --git a/src/Cosserat/mapping/LegendrePolynomialsMapping.inl b/src/Cosserat/mapping/LegendrePolynomialsMapping.inl index 27b4c71d..276463db 100644 --- a/src/Cosserat/mapping/LegendrePolynomialsMapping.inl +++ b/src/Cosserat/mapping/LegendrePolynomialsMapping.inl @@ -92,7 +92,6 @@ namespace sofa::component::mapping { helper::ReadAccessor< Data > velIn = dIn; helper::WriteOnlyAccessor< Data > out = dOut; - helper::ReadAccessor< Data > in = dIn; const auto sz = d_vectorOfCurvilinearAbscissa.getValue().size(); out.resize(sz-1); diff --git a/src/Cosserat/mapping/RigidDistanceMapping.cpp b/src/Cosserat/mapping/RigidDistanceMapping.cpp index cf69b244..3686ee20 100644 --- a/src/Cosserat/mapping/RigidDistanceMapping.cpp +++ b/src/Cosserat/mapping/RigidDistanceMapping.cpp @@ -19,7 +19,7 @@ * * * Contact information: contact@sofa-framework.org * ******************************************************************************/ -#pragma once +#define SOFA_COSSERAT_CPP_RigidDistanceMapping #include "RigidDistanceMapping.inl" #include #include diff --git a/src/Cosserat/mapping/RigidDistanceMapping.inl b/src/Cosserat/mapping/RigidDistanceMapping.inl index 73cf9391..d0e2f685 100644 --- a/src/Cosserat/mapping/RigidDistanceMapping.inl +++ b/src/Cosserat/mapping/RigidDistanceMapping.inl @@ -45,8 +45,7 @@ namespace sofa::component::mapping template RigidDistanceMapping::RigidDistanceMapping() - : m_toModel(NULL) - , d_index1(initData(&d_index1, "first_point", "index of the first model \n")) + : d_index1(initData(&d_index1, "first_point", "index of the first model \n")) , d_index2(initData(&d_index2, "second_point", "index of the second model \n")) , d_max(initData(&d_max, (Real)1.0e-2, "max", "the maximum of the deformation.\n")) , d_min(initData(&d_min, (Real)0.0, "min", "the minimum of the deformation.\n")) @@ -55,6 +54,7 @@ RigidDistanceMapping::RigidDistanceMapping() , d_index(initData(&d_index, "index", "if this parameter is false, you draw the beam with color " "according to the force apply to each beam")) , d_debug(initData(&d_debug, false, "debug", "show debug output.\n")) + , m_toModel(NULL) { d_debug.setValue(false); } @@ -139,8 +139,6 @@ void RigidDistanceMapping:: applyJ( const auto &m1Indices = d_index1.getValue(); const auto &m2Indices = d_index2.getValue(); - SpatialVector vDOF1, vDOF2; - for (sofa::Index index = 0; index < m_minInd; index++) { getVCenter(outVel[index]) = getVCenter(in2Vel[m2Indices[index]]) - getVCenter(in1Vel[m1Indices[index]]); getVOrientation(outVel[index]) = getVOrientation(in2Vel[m2Indices[index]]) - getVOrientation(in1Vel[m1Indices[index]]) ;