Skip to content

Commit

Permalink
Cleaning RigidDistanceMapping (#133)
Browse files Browse the repository at this point in the history
* cleaning

* Remove debug Data

* Remove countless aliases

* useless protected
  • Loading branch information
alxbilger authored Nov 14, 2024
1 parent 5d27dd5 commit 54ea0dd
Show file tree
Hide file tree
Showing 3 changed files with 120 additions and 179 deletions.
7 changes: 2 additions & 5 deletions src/Cosserat/mapping/RigidDistanceMapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,20 +21,17 @@
******************************************************************************/
#define SOFA_COSSERAT_CPP_RigidDistanceMapping
#include <Cosserat/mapping/RigidDistanceMapping.inl>
#include <sofa/defaulttype/VecTypes.h>
#include <sofa/defaulttype/RigidTypes.h>
#include <sofa/core/ObjectFactory.h>

namespace Cosserat::mapping
{

using namespace sofa::defaulttype;

// Register in the Factory
int RigidDistanceMappingClass = sofa::core::RegisterObject("Set the positions and velocities of points attached to a rigid parent")
int RigidDistanceMappingClass = sofa::core::RegisterObject("Maps two rigid frames to a single rigid frame representing their differences")
.add< RigidDistanceMapping< sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() ;


template class SOFA_COSSERAT_API RigidDistanceMapping< sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >;

} // namespace sofa.
} // namespace Cosserat::mapping
114 changes: 35 additions & 79 deletions src/Cosserat/mapping/RigidDistanceMapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,38 +21,20 @@
******************************************************************************/
#pragma once
#include <Cosserat/config.h>
#include <Cosserat/mapping/BaseCosseratMapping.h>

#include <sofa/core/BaseMapping.h>
#include <sofa/core/config.h>
#include <sofa/core/Multi2Mapping.h>
#include <sofa/defaulttype/SolidTypes.h>
#include <sofa/defaulttype/RigidTypes.h>
#include <sofa/helper/ColorMap.h>
#include <sofa/type/Transform.h>


namespace Cosserat::mapping
{
using sofa::defaulttype::SolidTypes ;
using sofa::core::objectmodel::BaseContext ;
using sofa::type::Matrix3;
using sofa::type::Matrix4;
using sofa::type::Vec3;
using sofa::type::Vec6;
using std::get;
using sofa::type::vector;
using sofa::Data;
using sofa::type::Mat;
using sofa::type::Vec4f;

/*!
* \class RigidDistanceMapping
* @brief Computes and map the length of the beams
*
* This is a component:
* https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/
*/
using Cosserat::mapping::BaseCosseratMapping;
//


template <class TIn1, class TIn2, class TOut>
class RigidDistanceMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>
{
Expand All @@ -67,55 +49,25 @@ class RigidDistanceMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>
/// Output Model Type
typedef TOut Out;

typedef typename In1::Coord Coord1;
typedef typename In1::Deriv Deriv1;
typedef typename In1::VecCoord In1VecCoord;
typedef typename In1::VecDeriv In1VecDeriv;
typedef typename In1::MatrixDeriv In1MatrixDeriv;
typedef Data<In1VecCoord> In1DataVecCoord;
typedef Data<In1VecDeriv> In1DataVecDeriv;
typedef Data<In1MatrixDeriv> In1DataMatrixDeriv;

typedef typename In2::Coord::value_type Real;
typedef typename In2::Coord Coord2;
typedef typename In2::Deriv Deriv2;
typedef typename In2::VecCoord In2VecCoord;
typedef typename In2::VecDeriv In2VecDeriv;
typedef typename In2::MatrixDeriv In2MatrixDeriv;
typedef Data<In2VecCoord> In2DataVecCoord;
typedef Data<In2VecDeriv> In2DataVecDeriv;
typedef Data<In2MatrixDeriv> In2DataMatrixDeriv;
typedef Mat<4,4,Real> Mat4x4;

typedef typename Out::VecCoord OutVecCoord;
typedef typename Out::Coord OutCoord;
typedef typename Out::Deriv OutDeriv;
typedef typename Out::VecDeriv OutVecDeriv;
typedef typename Out::MatrixDeriv OutMatrixDeriv;
typedef Data<OutVecCoord> OutDataVecCoord;
typedef Data<OutVecDeriv> OutDataVecDeriv;
typedef Data<OutMatrixDeriv> OutDataMatrixDeriv;

typedef typename SolidTypes<Real>::Transform Transform ;
typedef typename SolidTypes< Real>::SpatialVector SpatialVector ;
using Real = sofa::Real_t<In2>;

using Transform = sofa::type::Transform<Real>;
using SpatialVector = sofa::type::SpatialVector<Real>;

protected:
Data<vector<unsigned int> > d_index1 ;
Data<vector<unsigned int> > d_index2 ;
Data<Real> d_max ;
Data<Real> d_min ;
Data<Real> d_radius ;
Data<Vec4f> d_color;
Data<vector<unsigned int> > d_index;
Data<bool> d_debug ;
Data<vector<unsigned int> > d_index1;
Data<vector<unsigned int> > d_index2;
Data<Real> d_max;
Data<Real> d_min;
Data<Real> d_radius;
Data<sofa::type::RGBAColor> d_color;
Data<vector<unsigned int> > d_index;

sofa::core::State<Out>* m_toModel;

protected:
/// Constructor
RigidDistanceMapping() ;
/// Destructor
~RigidDistanceMapping() override = default;
RigidDistanceMapping();
~RigidDistanceMapping() override = default;

sofa::Index m_minInd{};
public:

Expand All @@ -126,22 +78,22 @@ class RigidDistanceMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>
/**********************MAPPING METHODS**************************/
void apply(
const sofa::core::MechanicalParams* /* mparams */,
const vector<OutDataVecCoord*>& dataVecOutPos,
const vector<const In1DataVecCoord*>& dataVecIn1Pos ,
const vector<const In2DataVecCoord*>& dataVecIn2Pos) override;
const vector<sofa::DataVecCoord_t<Out>*>& dataVecOutPos,
const vector<const sofa::DataVecCoord_t<In1>*>& dataVecIn1Pos ,
const vector<const sofa::DataVecCoord_t<In2>*>& dataVecIn2Pos) override;

void applyJ(
const sofa::core::MechanicalParams* /* mparams */,
const vector< OutDataVecDeriv*>& dataVecOutVel,
const vector<const In1DataVecDeriv*>& dataVecIn1Vel,
const vector<const In2DataVecDeriv*>& dataVecIn2Vel) override;
const vector< sofa::DataVecDeriv_t<Out>*>& dataVecOutVel,
const vector<const sofa::DataVecDeriv_t<In1>*>& dataVecIn1Vel,
const vector<const sofa::DataVecDeriv_t<In2>*>& dataVecIn2Vel) override;

//ApplyJT Force
void applyJT(
const sofa::core::MechanicalParams* /* mparams */,
const vector< In1DataVecDeriv*>& dataVecOut1Force,
const vector< In2DataVecDeriv*>& dataVecOut2RootForce,
const vector<const OutDataVecDeriv*>& dataVecInForce) override;
const vector< sofa::DataVecDeriv_t<In1>*>& dataVecOut1Force,
const vector< sofa::DataVecDeriv_t<In2>*>& dataVecOut2RootForce,
const vector<const sofa::DataVecDeriv_t<Out>*>& dataVecInForce) override;

void applyDJT(const sofa::core::MechanicalParams* /*mparams*/,
sofa::core::MultiVecDerivId /*inForce*/,
Expand All @@ -150,10 +102,14 @@ class RigidDistanceMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>
/// This method must be reimplemented by all mappings if they need to support constraints.
void applyJT(
const sofa::core::ConstraintParams* cparams ,
const vector< In1DataMatrixDeriv*>& dataMatOut1Const ,
const vector< In2DataMatrixDeriv*>& dataMatOut2Const ,
const vector<const OutDataMatrixDeriv*>& dataMatInConst) override;
const vector< sofa::DataMatrixDeriv_t<In1>*>& dataMatOut1Const ,
const vector< sofa::DataMatrixDeriv_t<In2>*>& dataMatOut2Const ,
const vector<const sofa::DataMatrixDeriv_t<Out>*>& dataMatInConst) override;

};

} // namespace sofa::component::mapping
#if !defined(SOFA_COSSERAT_CPP_RigidDistanceMapping)
extern template class SOFA_COSSERAT_API RigidDistanceMapping< sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >;
#endif

} // namespace Cosserat::mapping
Loading

0 comments on commit 54ea0dd

Please sign in to comment.